|
Noether
0.0.0
|
[GUI Plugins Example Simple] More...
Classes | |
| struct | AABBCenterOriginGenerator |
| Returns the center of the axis-aligned bounding box (AABB) as the origin. More... | |
| struct | AABBCenterOriginGeneratorWidget |
| class | AngleDoubleSpinBox |
| Double spin box widget class that supports angle units. More... | |
| class | BaseWidget |
| Base class for a widget that can configure tool path planning components. More... | |
| class | BiasedToolDragOrientationToolPathModifier |
| Transforms the waypoints to correspond with the edge of the ginding tool so that the edge of the tool is in contact with the media. More... | |
| class | BiasedToolDragOrientationToolPathModifierWidget |
| class | BoundaryEdgePlanner |
| Edge tool path planner that creates paths around the boundary edges of a mesh (exterior and interior) as identified by half-edge triangle mesh representation of the mesh. More... | |
| class | BoundaryEdgePlannerWidget |
| class | BSplineReconstruction |
| Smoothes a mesh by fitting a bspline surface to it. More... | |
| struct | CentroidOriginGenerator |
| Returns the centroid of the mesh vertices as the origin. More... | |
| struct | CentroidOriginGeneratorWidget |
| class | CircularLeadInModifier |
| Modifier that adjusts the parameters of the tool approach trajectory to the media. More... | |
| class | CircularLeadInToolPathModifierWidget |
| class | CircularLeadOutModifier |
| Modifier that adds exit waypoints in a circular arc (with fixed orientation) to the end of a trajectory. More... | |
| class | CircularLeadOutToolPathModifierWidget |
| class | CleanData |
| Merges duplicate points, removes unused points, and/or removes degenerate cells. More... | |
| class | CompoundMeshModifier |
| MeshModifier that cascades multiple MeshModifier instances in series. More... | |
| class | CompoundModifier |
| Modifier that chains together other modifiers. More... | |
| struct | ConcatenateModifier |
| Concatenates all input tool paths into a single tool path. More... | |
| struct | ConcatenateModifierWidget |
| class | ConfigurableTPPPipelineWidget |
| class | CrossHatchPlaneSlicerRasterPlannerWidget |
| struct | DirectionGenerator |
| Interface for generating the direction of raster paths. More... | |
| class | DirectionGeneratorWidgetPlugin |
| WidgetPlugin implementation specifically for BaseWidget instances that configure direction generators. More... | |
| struct | DirectionOfTravelOrientationModifier |
| Aligns the x-axis of all waypoints with the direction of travel between adjacent waypoints. More... | |
| struct | DirectionOfTravelOrientationModifierWidget |
| class | DistanceDoubleSpinBox |
| Double spin box widget class that supports distance units. More... | |
| class | EdgePlanner |
| A specification of the tool path planner interface for generating paths around the edges of surfaces. More... | |
| class | EuclideanClusteringMeshModifier |
| MeshModifier that separates the mesh into clusters. More... | |
| class | EuclideanClusteringMeshModifierWidget |
| struct | ExtrudedPolygonSubMeshExtractor |
| Extracts the submesh with the vertices captured inside an extruded polygon defined by the input boundary points. More... | |
| struct | ExtrudedPolygonSubsetExtractor |
| Extracts the submesh with the vertices captured inside an extruded polygon defined by the input boundary points. More... | |
| class | FaceMidpointSubdivisionMeshModifier |
| MeshModifier that applies iterative midpoint subdivision to create smaller mesh faces. More... | |
| class | FaceMidpointSubdivisionMeshModifierWidget |
| class | FaceSubdivisionByAreaMeshModifier |
| MeshModifier that subdivides mesh faces into smaller faces until all faces have less than the specified maximum area. More... | |
| class | FaceSubdivisionByAreaMeshModifierWidget |
| class | FaceSubdivisionMeshModifier |
| MeshModifier that subdivides mesh faces until a user-defined criteria is met. More... | |
| class | Factory |
| Factory for creating tool path planning components from plugins. More... | |
| class | FillHoles |
Fills holes in the mesh using vtkFillHoles More... | |
| class | FillHolesModifierWidget |
| class | FixedDirectionGenerator |
| Generates the raster direction based on a fixed input. More... | |
| class | FixedDirectionGeneratorWidget |
| class | FixedOrientationModifier |
| Aligns the orientation of each waypoint with the existing waypoint normal (z-axis) and the specified reference x-axis direction. More... | |
| class | FixedOrientationModifierWidget |
| class | FixedOriginGenerator |
| Returns a fixed point as the origin. More... | |
| class | FixedOriginGeneratorWidget |
| class | JoinCloseSegmentsToolPathModifier |
| Joins tool path segments that are within a specified Cartesian distance of one another. More... | |
| class | JoinCloseSegmentsToolPathModifierWidget |
| class | LinearApproachModifier |
| Adds a series of waypoints in a linear pattern off the first waypoint in a tool path. More... | |
| class | LinearApproachToolPathModifierWidget |
| class | LinearDepartureModifier |
| Adds a series of waypoints in a linear pattern off the last waypoint in a tool path. More... | |
| class | LinearDepartureToolPathModifierWidget |
| struct | MeshModifier |
| A common interface for mesh modifications. More... | |
| class | MeshModifierWidgetPlugin |
| WidgetPlugin implementation specifically for BaseWidget instances that configure mesh modifiers. More... | |
| class | MinimumSegmentLengthToolPathModifier |
| Prunes tool path segments whose lengths are less than the specified minimum length. More... | |
| class | MinimumSegmentLengthToolPathModifierWidget |
| class | MovingAverageOrientationSmoothingModifier |
| Applies a moving average filter to waypoints in each tool path segment to smooth their orientations. More... | |
| class | MovingAverageOrientationSmoothingModifierWidget |
| class | MultiToolPathPlanner |
| Runs multiple tool path planners serially and concatenates their outputs together. More... | |
| class | NormalEstimationPCLMeshModifier |
| Estimates vertex normals of an input mesh using PCL. More... | |
| class | NormalEstimationPCLMeshModifierWidget |
| class | NormalsFromMeshFacesMeshModifier |
| MeshModifier that assigns vertex normals using mesh faces. More... | |
| class | NormalsFromMeshFacesMeshModifierWidget |
| class | OffsetModifier |
| Offsets the tool path by a fixed pose. More... | |
| class | OffsetModifierWidget |
| class | OffsetOriginGenerator |
| Returns the origin as the origin of another specified origin generator plus a fixed offset. More... | |
| class | OneTimeCompoundModifier |
| Modifier that chains together one-time style modifiers. More... | |
| struct | OneTimeToolPathModifier |
| An extension of the ToolPathModifier interface that requires a modifier to not cause additional changes if run again. More... | |
| struct | OriginGenerator |
| Interface for setting the start point from which to generate toolpaths. More... | |
| class | OriginGeneratorWidgetPlugin |
| WidgetPlugin implementation specifically for BaseWidget instances that configure origin generators. More... | |
| class | PCARotatedDirectionGenerator |
| Rotates a direction vector provided by another direction generator about the smallest principal axis of the input mesh. More... | |
| class | PlaneSlicerLegacyRasterPlanner |
| class | PlaneSlicerLegacyRasterPlannerWidget |
| class | PlaneSlicerRasterPlanner |
| An implementation of RasterPlanner using a series of parallel cutting planes. More... | |
| class | PlaneSlicerRasterPlannerWidget |
| class | Plugin |
| Base class for a plugin that can generate a tool path planning component (e.g., mesh modifier, tool path planner, tool path modifier). More... | |
| class | PluginLoaderWidget |
| Widget for loading widget plugins. More... | |
| class | PrincipalAxisDirectionGenerator |
| Generates the raster direction along the largest principal axis of the input mesh. More... | |
| class | PrincipalAxisDirectionGeneratorWidget |
| class | RansacCylinderFitMeshModifier |
| MeshModifier that fits a specifiable number of cylinders to the input mesh and returns the fitted primitive models. More... | |
| class | RansacCylinderFitMeshModifierWidget |
| class | RansacCylinderProjectionMeshModifier |
| MeshModifier that fits a specifiable number of cylinders to the input mesh and projects the inlier vertices onto the fitted cylinder models. More... | |
| class | RansacCylinderProjectionMeshModifierWidget |
| class | RansacPlaneProjectionMeshModifier |
| MeshModifier that fits planes to the input mesh and projects the vertices onto the fitted planes. More... | |
| class | RansacPlaneProjectionMeshModifierWidget |
| class | RansacPrimitiveFitMeshModifier |
| Mesh modifier that fits a specifiable number of model primitives to the input mesh. More... | |
| class | RansacPrimitiveFitMeshModifierWidget |
| struct | RasterOrganizationModifier |
| Organizes a tool path into a raster-style pattern. More... | |
| struct | RasterOrganizationModifierWidget |
| class | RasterPlanner |
| A specification of the tool path planner for covering surfaces in repeating, evenly spaced path lines. More... | |
| class | RasterPlannerWidget |
| struct | SimplePlugin |
| Template for a simple implementation of Plugin. More... | |
| struct | SimpleWidgetPlugin |
| Template for a simple implementation of WidgetPlugin. More... | |
| struct | SnakeOrganizationModifier |
| Organizes a tool path into a snake-style pattern. More... | |
| struct | SnakeOrganizationModifierWidget |
| class | SplineExtrapolationToolPathModifier |
| Extrapolates the tool path. More... | |
| struct | SplineExtrapolationToolPathModifierWidget |
| class | StandardEdgePathsOrganizationModifier |
| Organizes a set of tool paths into a standard configuration for edge paths. More... | |
| class | StandardEdgePathsOrganizationModifierWidget |
| struct | SubMeshExtractor |
| Base class for extracting a submesh from a mesh given a set of boundary points. More... | |
| struct | SubsetExtractor |
| Base class for extracting a point cloud subset from an input given a set of boundary points. More... | |
| class | ToolDragOrientationToolPathModifier |
| Transforms the waypoints to correspond with the center of the ginding tool so that the edge of the tool is in contact with the media. More... | |
| class | ToolDragOrientationToolPathModifierWidget |
| struct | ToolPathModifier |
| A common interface for functions that alter a generated toolpath. More... | |
| class | ToolPathModifierWidgetPlugin |
| WidgetPlugin implementation specifically for BaseWidget instances that configure tool path modifiers. More... | |
| struct | ToolPathPlanner |
| Interface for a tool path planner that operates on a mesh. More... | |
| class | ToolPathPlannerPipeline |
| class | ToolPathPlannerWidgetPlugin |
| WidgetPlugin implementation specifically for BaseWidget instances that configure tool path planners. More... | |
| class | TPPPipelineWidget |
| Widget for creating a tool path planning pipeline. More... | |
| class | TPPWidget |
| Basic tool path planning widget. More... | |
| struct | UniformOrientationModifier |
| Aligns the x-axis of all waypoints with the direction of travel of the first two waypoints. More... | |
| struct | UniformOrientationModifierWidget |
| class | UniformSpacingModifier |
| The UniformSpacingLinearModifier class. More... | |
| class | UniformSpacingModifierWidget |
| class | WidgetFactory |
| Extends the Factory class to be able to load widget plugins for the GUI. More... | |
| class | WidgetPlugin |
Base class for a plugin that can generate a BaseWidget<T> for configuring a tool path planning component (e.g., mesh modifier, tool path planner, tool path modifier). More... | |
| class | WindowedSincSmoothing |
| Uses vtkWindowedSincPolyDataFilter to smooth the mesh. More... | |
Typedefs | |
| using | ToolPathWaypoint = Eigen::Isometry3d |
| A point on a surface that makes up part of a path. | |
| using | ToolPathSegment = std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > |
| A set of contiguous ToolPathWaypoint that lie on the same line created by a "slice" through a surface. | |
| using | ToolPath = std::vector< ToolPathSegment > |
| A set of ToolPathSegment that lie on the same line created by a tool path "slice", but are not connected (e.g. due to a hole in the mesh) | |
| using | ToolPaths = std::vector< ToolPath > |
| A set of ToolPath (i.e. rasters) generated by various slices through a surface. | |
| using | ToolPathPlannerPlugin = Plugin< ToolPathPlanner > |
| Plugin interface for creating a ToolPathPlanner. | |
| using | DirectionGeneratorPlugin = Plugin< DirectionGenerator > |
| Plugin interface for creating a DirectionGenerator. | |
| using | OriginGeneratorPlugin = Plugin< OriginGenerator > |
| Plugin interface for creating an OriginGenerator. | |
| using | ToolPathModifierPlugin = Plugin< ToolPathModifier > |
| Plugin interface for creating a ToolPathModifier. | |
| using | MeshModifierPlugin = Plugin< MeshModifier > |
| Plugin interface for creating a MeshModifier. | |
| using | MeshTraits = pcl::geometry::DefaultMeshTraits< std::uint32_t > |
| using | TriangleMesh = pcl::geometry::TriangleMesh< MeshTraits > |
Enumerations | |
| enum class | LineStyle { INTRA_SEGMENT = 0 , INTER_SEGMENT , INTER_PATH } |
Functions | |
| QStringList | toQStringList (const std::vector< std::string > &list) |
| void | overwriteWidget (QLayout *layout, QWidget *&from, QWidget *to) |
| Overwrites one widget within a layout with another widget. | |
| EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN (FaceMidpointSubdivisionMeshModifierWidget, FaceMidpointSubdivision) | |
| EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN (FaceSubdivisionByAreaMeshModifierWidget, FaceSubdivisionByArea) | |
| EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN (StandardEdgePathsOrganizationModifierWidget, StandardEdgePathsOrganization) EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(MovingAverageOrientationSmoothingModifierWidget | |
| vtkSmartPointer< vtkTransform > | toVTK (const Eigen::Isometry3d &mat) |
| vtkSmartPointer< vtkPropAssembly > | createToolPathActors (const std::vector< ToolPaths > &tool_paths, vtkAlgorithmOutput *waypoint_shape_output_port) |
| vtkSmartPointer< vtkLeaderActor2D > | createLineActor (const Eigen::Isometry3d &point1, const Eigen::Isometry3d &point2, LineStyle lineStyle, bool include_arrow) |
| vtkSmartPointer< vtkPropAssembly > | createToolPathPolylineActor (const std::vector< ToolPaths > &tool_paths, vtkAlgorithmOutput *waypoint_shape_output_port) |
| vtkSmartPointer< vtkPropAssembly > | createMeshActors (const std::vector< pcl::PolygonMesh > &meshes) |
| pcl::PolygonMesh | extractSubMeshFromInlierVertices (const pcl::PolygonMesh &input_mesh, const std::vector< int > &inlier_vertex_indices) |
| Extracts the sub-mesh from inlier vertices. | |
| Eigen::Isometry3d | sample (const Eigen::Spline3d &spline, const double u, const Eigen::Vector3d &ref_z) |
| std::vector< double > | computeSpanLengths (const Eigen::Spline3d &spline) |
| std::vector< double > | computeKnotDistances (const Eigen::Spline3d &spline) |
| double | computeLength (const Eigen::Spline3d &spline) |
| double | computeSplineParameterAtDistance (const Eigen::Spline3d &spline, const double dist, const double tol=1.0e-4) |
| std::vector< double > | computeEquidistantKnots (const Eigen::Spline3d &spline, const double knot_spacing, const bool include_endpoints=false, const double tol=1.0e-4) |
| Eigen::Vector3d | estimateToolPathDirection (const ToolPath &tool_path) |
| Estimates the direction of travel of a tool path by averaging the vectors between adjacent waypoints. | |
| Eigen::Vector3d | estimateRasterDirection (const ToolPaths &tool_paths, const Eigen::Vector3d &reference_tool_path_dir) |
| Estimates the raster direction of a set of tool paths by returning the component of the vector from the first point in the first segment of the first tool path) to the first waypoint in the first segment of the last tool path that is perpendicular to the nominal tool path direction. | |
| std::vector< pcl::PCLPointField >::const_iterator | findField (const std::vector< pcl::PCLPointField > &fields, const std::string &name) |
| std::vector< pcl::PCLPointField >::const_iterator | findFieldOrThrow (const std::vector< pcl::PCLPointField > &fields, const std::string &name) |
| bool | hasNormals (const pcl::PCLPointCloud2 &cloud) |
| Eigen::Map< const Eigen::Vector3f > | getPoint (const pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Map< Eigen::Vector3f > | getPoint (pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Map< const Eigen::Vector3f > | getNormal (const pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Map< Eigen::Vector3f > | getNormal (pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Map< const Eigen::Vector< uint8_t, 4 > > | getRgba (const pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Map< Eigen::Vector< uint8_t, 4 > > | getRgba (pcl::PCLPointCloud2 &cloud, const std::uint32_t pt_idx) |
| Eigen::Vector3f | getFaceNormal (const pcl::PolygonMesh &mesh, const pcl::Vertices &polygon) |
| TriangleMesh | createTriangleMesh (const pcl::PolygonMesh &input) |
| Creates a triangle mesh representation of the input polygon mesh. | |
| std::tuple< double, std::vector< double > > | computeLength (const ToolPathSegment &segment) |
| Computes the length of a tool path segment. | |
| void | printException (const std::exception &e, std::ostream &ss, int level=0) |
| Unrolls an exception and captures content from all nested exceptions. | |
| pcl::PolygonMesh | createPlaneMesh (const float lx=1.0, const float ly=1.0, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| pcl::PolygonMesh | createEllipsoidMesh (const float rx=1.0, const float ry=1.0, const float rz=1.5, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(M_PI), const float phi_range=static_cast< float >(2.0 *M_PI), const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| pcl::PolygonMesh | createCylinderMesh (const float radius, const float length, const std::size_t resolution=20lu, std::size_t vertical_resolution=2u, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| pcl::PolygonMesh | createCylinderMesh (const float radius, const float length, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| pcl::PolygonMesh | createCylinderMeshWithUniformTriangles (const float radius, const float length, const std::size_t resolution=20lu, const float theta_range=static_cast< float >(2.0 *M_PI), const bool include_caps=true, const Eigen::Isometry3d &origin=Eigen::Isometry3d::Identity()) |
| void | projectInPlace (pcl::PCLPointCloud2 &cloud, const Eigen::VectorXf &model_coefficients) |
| Projects points onto the cylinder model in-place. | |
| void | projectInPlace (pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &plane_coeffs) |
| EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN (FaceMidpointSubdivisionMeshModifier, FaceMidpointSubdivision) | |
| EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN (FaceSubdivisionByAreaMeshModifier, FaceSubdivisionByArea) | |
| EXPORT_TOOL_PATH_MODIFIER_PLUGIN (Plugin_CompoundToolPathModifier, CompoundToolPathModifier) | |
| EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN (BoundaryEdgePlanner, Boundary) | |
| double | simpsonComposite38 (const std::function< Eigen::ArrayXd(double)> &f, const double a, const double b, const int n=3) |
| std::tuple< double, double, double > | estimateSplineParameterAtDistance (const Eigen::Spline3d::KnotVectorType &knots, const std::vector< double > &knot_distances, const double dist) |
| double | computeSplineParameterAtDistance (const Eigen::Spline3d::KnotVectorType &knots, const std::vector< double > &knot_distances, std::function< Eigen::Array3d(const double)> s_dot, const double dist, const double tol) |
| Helper function for computSplineParameterAtDistance that avoids recomputing knot distances. | |
| template<typename T > | |
| std::string | getClassName (const T &obj) |
| Extracts the demangled class name behind the namespace for printing in unit test. | |
| template<typename T > | |
| std::string | print (const testing::TestParamInfo< std::shared_ptr< T > > info) |
| Prints name of class for unit test output. | |
[Plugins Example Simple]
[GUI Plugins Example Complex]
[Plugins Example Complex]
| Eigen::Isometry3d noether::sample | ( | const Eigen::Spline3d & | spline, |
| const double | u, | ||
| const Eigen::Vector3d & | ref_z | ||
| ) |
Samples the input spline at the given spline parameter to create a 6-DoF pose, where the x-axis is aligned with the first derivative of the spline.
| spline | |
| u | Spline parameter (on [0, 1]) at which to sample the spline |
| ref_z | Reference z-axis for use in computing the pose orientation |
| std::vector< double > noether::computeSpanLengths | ( | const Eigen::Spline3d & | spline | ) |
Computes the lengths (m) of each polynomial span of the spline. This method applies Simpson's composite 3/8 rule to numerically integrate the first derivative of each polynomial segment of the spline to compute the distance
| spline |
n_knots - 1) | std::vector< double > noether::computeKnotDistances | ( | const Eigen::Spline3d & | spline | ) |
Computes the distances (m) along the spline to each knot. This method performs a cumulative sum of the span lengths (given by computeSpanLengths) to return the total distance (m) along the spline to each knot
| spline |
n_knots) | double noether::computeLength | ( | const Eigen::Spline3d & | spline | ) |
Computes the length (m) of the input spline. This method sums the length of all polynomial spans of the spline, given by computeSpanLengths
| spline |
| double noether::computeSplineParameterAtDistance | ( | const Eigen::Spline3d & | spline, |
| const double | dist, | ||
| const double | tol = 1.0e-4 |
||
| ) |
Computes the spline parameter at a specific distance along on the spline
| spline | |
| dist | Distance (m) along spline. When this value is negative, or greater than the length of the spline the first/last polynomial segment will be extrapolated. |
| tol | Error tolerance (m) with which to calculate the distance |
| std::vector< double > noether::computeEquidistantKnots | ( | const Eigen::Spline3d & | spline, |
| const double | knot_spacing, | ||
| const bool | include_endpoints = false, |
||
| const double | tol = 1.0e-4 |
||
| ) |
Computes equidistant knot points along a spline. If the endpoints of the spline are included, the remaining equally spaced points will be centered in between them.
| spline | |
| knot_spacing | Spacing (m) between knots on the spline |
| include_endpoints | Flag to indicate that the spline parameters for the endpoints of the spline (i.e., 0 and 1) should be included in the output |
| tol | Error tolerance (m) for calculating the distance along the spline |
| void noether::printException | ( | const std::exception & | e, |
| std::ostream & | ss, | ||
| int | level = 0 |
||
| ) |
| double noether::simpsonComposite38 | ( | const std::function< Eigen::ArrayXd(double)> & | f, |
| const double | a, | ||
| const double | b, | ||
| const int | n = 3 |
||
| ) |
Implments Simpson's composite 3/8 rule for approximate numerical integration
| f | Function to integrate (e.g., spline derivative) |
| a | Start location (e.g., spline start parameter) |
| b | End location (e.g., spline end parameter) |
| n | Number of subdivisions (must be a multiple of 3) |
| std::tuple< double, double, double > noether::estimateSplineParameterAtDistance | ( | const Eigen::Spline3d::KnotVectorType & | knots, |
| const std::vector< double > & | knot_distances, | ||
| const double | dist | ||
| ) |
Returns the 1) distance and 2) value of the closest knot to the desired distance value and 3) a knot offset value from the closest knot that approximates the location of the desired distance. The estimated spline parameter at the input distance is the knot value plus the offset.