LArSoft  v10_04_05
Liquid Argon Software toolkit - https://larsoft.org/
geo::PlaneGeo Class Reference

Geometry information for a single wire plane.The plane is represented in the geometry by a solid which contains wires. Currently, only box solids are well supported. The box which is representation of the plane has some thickness, and it should not be assumed that the wires are in the median section of it, that is, the center of the box may not lie on the plane defined by the wires. More...

#include "PlaneGeo.h"

Classes

struct  PlaneGeoCoordinatesTag
 Tag for vectors in the "local" GDML coordinate frame of the plane. More...
 
struct  RectSpecs
 
struct  WidthDepthReferenceTag
 Tag for plane frame base vectors. More...
 
struct  WireCoordinateReferenceTag
 Tag for wire base vectors. More...
 

Public Types

using ID_t = PlaneID
 
using WireCollection_t = std::vector< WireGeo >
 
using GeoNodePath_t = std::vector< TGeoNode const * >
 
using ElementIteratorBox = WireCollection_t const &
 Type returned by IterateElements(). More...
 
using Rect = lar::util::simple_geo::Rectangle< double >
 Type for description of rectangles. More...
 
Types for geometry-local reference vectors.

These types represents points and displacement vectors in the reference frame defined in the plane geometry box from the GDML geometry description.

No alias is explicitly defined for the LArSoft global vector types, geo::Point_t and geo::Vector_t.

Remember the LocalPoint_t and LocalVector_t vectors from different instances of geo::PlaneGeo have the same type but are not compatible.

using LocalPoint_t = Point3DBase_t< PlaneGeoCoordinatesTag >
 Type of points in the local GDML wire plane frame. More...
 
using LocalVector_t = Vector3DBase_t< PlaneGeoCoordinatesTag >
 Type of displacement vectors in the local GDML wire plane frame. More...
 
Types for vectors in the wire coordinate frame.
using WireCoordProjection_t = ROOT::Math::DisplacementVector2D< ROOT::Math::Cartesian2D< double >, WireCoordinateReferenceTag >
 Type for projections in the wire base representation. More...
 
using WireDecomposer_t = Decomposer< Vector_t, Point_t, WireCoordProjection_t >
 Type used for plane decompositions on wire base. More...
 
using WireDecomposedVector_t = WireDecomposer_t::DecomposedVector_t
 Type describing a 3D point or vector decomposed on a plane on wire base. More...
 
Types for vectors in the width/depth coordinate frame.
using WidthDepthProjection_t = ROOT::Math::DisplacementVector2D< ROOT::Math::Cartesian2D< double >, WidthDepthReferenceTag >
 
using WidthDepthDisplacement_t = ROOT::Math::DisplacementVector2D< ROOT::Math::Cartesian2D< double >, WidthDepthReferenceTag >
 Type for vector projections in the plane frame base representation. More...
 
using WidthDepthDecomposer_t = Decomposer< Vector_t, Point_t, WidthDepthProjection_t >
 Type used for plane decompositions on plane frame (width/depth). More...
 
using WDDecomposedVector_t = WidthDepthDecomposer_t::DecomposedVector_t
 

Public Member Functions

 PlaneGeo (TGeoNode const *node, TransformationMatrix &&trans, WireCollection_t &&wires)
 Construct a representation of a single plane of the detector. More...
 
TGeoVolume const * TPCVolume () const
 
double Width () const
 Return the width of the plane. More...
 
double Depth () const
 Return the depth of the plane. More...
 
BoxBoundedGeo BoundingBox () const
 
WireGeo const & Wire (unsigned int iwire) const
 
auto WirePtr (unsigned int iwire) const
 Returns the wire number iwire from this plane. More...
 
WireGeo const & FirstWire () const
 Return the first wire in the plane. More...
 
WireGeo const & MiddleWire () const
 Return the middle wire in the plane. More...
 
WireGeo const & LastWire () const
 Return the last wire in the plane. More...
 
WireGeo const & NearestWire (Point_t const &pos) const
 Returns the wire closest to the specified position. More...
 
WireID ClosestWireID (WireID::WireID_t wireNo) const
 Returns the closest valid wire ID to the specified wire. More...
 
WireID ClosestWireID (WireID const &wireid) const
 Returns the closest valid wire ID to the specified wire. More...
 
Rect const & ActiveArea () const
 Returns an area covered by the wires in the plane. More...
 
template<typename Stream >
void PrintPlaneInfo (Stream &&out, std::string indent="", unsigned int verbosity=1) const
 Prints information about this plane. More...
 
std::string PlaneInfo (std::string indent="", unsigned int verbosity=1) const
 Returns a string with plane information. More...
 
double WireCoordinate (Point_t const &point) const
 Returns the coordinate of the point on the plane, in wire units. More...
 
WidthDepthProjection_t DeltaFromPlane (WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
 Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the plane. More...
 
WidthDepthProjection_t DeltaFromPlane (WidthDepthProjection_t const &proj, double margin=0.0) const
 Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the area of plane. More...
 
WidthDepthProjection_t DeltaFromActivePlane (WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
 Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the active area of plane. More...
 
WidthDepthProjection_t DeltaFromActivePlane (WidthDepthProjection_t const &proj, double margin=0.0) const
 Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the active area of plane. More...
 
WidthDepthProjection_t MoveProjectionToPlane (WidthDepthProjection_t const &proj) const
 Returns the projection, moved onto the plane if necessary. More...
 
void SortWires (Compare< WireGeo > cmp)
 Apply sorting to WireGeo objects. More...
 
void UpdateAfterSorting (PlaneID planeid, BoxBoundedGeo const &TPCbox)
 Performs all needed updates after the TPC has sorted the planes. More...
 
Plane properties
View_t View () const
 Which coordinate does this plane measure. More...
 
Orient_t Orientation () const
 What is the orientation of the plane. More...
 
double ThetaZ () const
 Angle of the wires from positive z axis; $ \theta_{z} \in [ 0, \pi ]$. More...
 
double PhiZ () const
 Angle from positive z axis of the wire coordinate axis, in radians. More...
 
double SinPhiZ () const
 Sine of PhiZ() More...
 
double CosPhiZ () const
 Cosine of PhiZ() More...
 
PlaneID const & ID () const
 Returns the identifier of this plane. More...
 
Plane size and coordinates
Vector_t const & WidthDir () const
 Return the direction of plane width. More...
 
Vector_t const & DepthDir () const
 Return the direction of plane depth. More...
 
Wire access
unsigned int Nwires () const
 Number of wires in this plane. More...
 
unsigned int NElements () const
 Number of wires in this plane. More...
 
bool HasWire (unsigned int iwire) const
 Returns whether a wire with index iwire is present in this plane. More...
 
bool HasElement (unsigned int iwire) const
 Returns whether a wire with index iwire is present in this plane. More...
 
bool HasWire (WireID const &wireid) const
 Returns whether the wire in wireid is present in this plane. More...
 
bool HasElement (WireID const &wireid) const
 Returns whether the wire in wireid is present in this plane. More...
 
WireGeo const & Wire (WireID const &wireid) const
 Returns the wire in wireid from this plane. More...
 
WireGeo const & GetElement (WireID const &wireid) const
 Returns the wire in wireid from this plane. More...
 
auto WirePtr (WireID const &wireid) const
 Returns the wire in wireid from this plane. More...
 
auto GetElementPtr (WireID const &wireid) const
 Returns the wire in wireid from this plane. More...
 
Plane geometry properties
double WirePitch () const
 Return the wire pitch (in centimeters). It is assumed constant. More...
 
bool WireIDincreasesWithZ () const
 Returns whether the higher z wires have higher wire ID. More...
 
Vector_t const & GetNormalDirection () const
 Returns the direction normal to the plane. More...
 
Vector_t const & GetIncreasingWireDirection () const
 Returns the direction of increasing wires. More...
 
Point_t const & GetCenter () const
 Returns the centre of the wire plane in world coordinates [cm]. More...
 
Point_t GetBoxCenter () const
 Returns the centre of the box representing the plane. More...
 
Vector_t const & GetWireDirection () const
 Returns the direction of the wires. More...
 
WireID NearestWireID (Point_t const &pos) const
 Returns the ID of wire closest to the specified position. More...
 
double DistanceFromPlane (Point_t const &point) const
 Returns the distance of the specified point from the wire plane. More...
 
void DriftPoint (Point_t &position, double distance) const
 Shifts the position of an electron drifted by a distance. More...
 
void DriftPoint (Point_t &position) const
 Shifts the position along drift direction to fall on the plane. More...
 
double InterWireProjectedDistance (WireCoordProjection_t const &projDir) const
 Returns the distance between wires along the specified direction. More...
 
double InterWireDistance (Vector_t const &dir) const
 Returns the distance between wires along the specified direction. More...
 
double InterWireProjectedDistance (Vector_t const &dir) const
 Returns the distance between wires along the specified direction. More...
 
Projections on wire length/wire coordinate direction base

These methods deal with projection of points and vectors on the plane, using a geometric reference base which is dependent on the wire direction. This is useful for plane reconstruction.

double PlaneCoordinateFrom (Point_t const &point, WireGeo const &refWire) const
 Returns the coordinate of point on the plane respect to a wire. More...
 
double PlaneCoordinate (Point_t const &point) const
 Returns the coordinate of the point on the plane. More...
 
WireDecomposedVector_t DecomposePoint (Point_t const &point) const
 Decomposes a 3D point in two components. More...
 
Point_t ProjectionReferencePoint () const
 Returns the reference point used by PointProjection(). More...
 
WireCoordProjection_t Projection (Point_t const &point) const
 Returns the projection of the specified point on the plane. More...
 
WireCoordProjection_t Projection (Vector_t const &v) const
 Returns the projection of the specified vector on the plane. More...
 
Vector_t ComposeVector (WireDecomposedVector_t const &decomp) const
 Returns the 3D vector from composition of projection and distance. More...
 
Vector_t ComposeVector (double distance, WireCoordProjection_t const &proj) const
 Returns the 3D vector from composition of projection and distance. More...
 
Point_t ComposePoint (WireDecomposedVector_t const &decomp) const
 Returns the 3D point from composition of projection and distance. More...
 
Point_t ComposePoint (double distance, WireCoordProjection_t const &proj) const
 Returns the 3D point from composition of projection and distance. More...
 
Projection on width/depth plane

These methods deal with projection of points and vectors on the plane, using a geometric reference base which is not dependent on the wire direction. This is more useful when comparing with the TPC or other planes.

WDDecomposedVector_t DecomposePointWidthDepth (Point_t const &point) const
 Decomposes a 3D point in two components. More...
 
WidthDepthProjection_t PointWidthDepthProjection (Point_t const &point) const
 Returns the projection of the specified point on the plane. More...
 
WidthDepthProjection_t VectorWidthDepthProjection (Vector_t const &v) const
 Returns the projection of the specified vector on the plane. More...
 
bool isProjectionOnPlane (Point_t const &point) const
 Returns if the projection of specified point is within the plane. More...
 
Point_t MovePointOverPlane (Point_t const &point) const
 Returns the point, moved so that its projection is over the plane. More...
 
Point_t ComposePoint (WDDecomposedVector_t const &decomp) const
 Returns the 3D vector from composition of projection and distance. More...
 
Point_t ComposePoint (double distance, WidthDepthProjection_t const &proj) const
 Returns the 3D point from composition of projection and distance. More...
 
Coordinate transformation

Local points and displacement vectors are described by the types geo::PlaneGeo::LocalPoint_t and geo::PlaneGeo::LocalVector_t, respectively.

Point_t toWorldCoords (LocalPoint_t const &local) const
 Transform point from local plane frame to world frame. More...
 
Vector_t toWorldCoords (LocalVector_t const &local) const
 Transform direction vector from local to world. More...
 
LocalPoint_t toLocalCoords (Point_t const &world) const
 Transform point from world frame to local plane frame. More...
 
LocalVector_t toLocalCoords (Vector_t const &world) const
 Transform direction vector from world to local. More...
 
Setters
void SetView (View_t view)
 Set the signal view (for TPCGeo). More...
 

Static Public Member Functions

static std::string ViewName (View_t view)
 Returns the name of the specified view. More...
 
static std::string OrientationName (Orient_t orientation)
 Returns the name of the specified orientation. More...
 

Static Public Attributes

static constexpr unsigned int MaxVerbosity = 6
 Maximum value for print verbosity. More...
 

Private Types

using LocalTransformation_t = LocalTransformationGeo< ROOT::Math::Transform3D, LocalPoint_t, LocalVector_t >
 

Private Member Functions

TGeoVolume const & Volume () const
 
void DetectGeometryDirections ()
 Sets the geometry directions. More...
 
Vector_t GetNormalAxis () const
 Returns a direction normal to the plane (pointing is not defined). More...
 
void UpdatePlaneNormal (BoxBoundedGeo const &TPCbox)
 Updates the cached normal to plane versor; needs the TPC box coordinates. More...
 
void UpdateWidthDepthDir ()
 Updates the cached depth and width direction. More...
 
void UpdateIncreasingWireDir ()
 Updates the cached direction to increasing wires. More...
 
void UpdateWireDir ()
 Updates the cached direction to wire. More...
 
void UpdateOrientation ()
 Updates plane orientation. More...
 
void UpdateWirePitch ()
 Updates the stored wire pitch. More...
 
void UpdateWirePlaneCenter ()
 Updates the stored wire plane center. More...
 
void UpdatePhiZ ()
 Updates the stored $ \phi_{z} $. More...
 
void UpdateView ()
 Updates the stored view. More...
 
void UpdateWirePitchSlow ()
 Updates the stored wire pitch with a slower, more robust algorithm. More...
 
void UpdateDecompWireOrigin ()
 Updates the position of the wire coordinate decomposition. More...
 
void UpdateActiveArea ()
 Updates the internally used active area. More...
 
bool shouldFlipWire (WireGeo const &wire) const
 Whether the specified wire should have start and end swapped. More...
 

Private Attributes

TGeoNode const * fNode
 Node within full geometry. More...
 
LocalTransformation_t fTrans
 Plane to world transform. More...
 
View_t fView {kUnknown}
 Does this plane measure U, V, or W? More...
 
Orient_t fOrientation {kVertical}
 Is the plane vertical or horizontal? More...
 
WireCollection_t fWire
 List of wires in this plane. More...
 
double fWirePitch {0.}
 Pitch of wires in this plane. More...
 
double fSinPhiZ {0.}
 Sine of $ \phi_{z} $. More...
 
double fCosPhiZ {0.}
 Cosine of $ \phi_{z} $. More...
 
Vector_t fNormal
 
WireDecomposer_t fDecompWire {}
 
WidthDepthDecomposer_t fDecompFrame {}
 
RectSpecs fFrameSize
 
Rect fActiveArea
 Area covered by wires in frame base. More...
 
Point_t fCenter {}
 Center of the plane, lying on the wire plane. More...
 
PlaneID fID
 ID of this plane. More...
 

Detailed Description

Geometry information for a single wire plane.

The plane is represented in the geometry by a solid which contains wires. Currently, only box solids are well supported. The box which is representation of the plane has some thickness, and it should not be assumed that the wires are in the median section of it, that is, the center of the box may not lie on the plane defined by the wires.

The plane defines two local reference frames:

  • The first, depending on wire directions and therefore called "wire base", is defined by the normal to the plane (pointing toward the center of the TPC), the direction of the wires, and the direction that the wires measure. This is a positive orthogonal base. Note that for this base to be correctly defined, the Geometry service has to provide external information (for example, where the center of the TPC is).
  • The second, depending only on the shape of the plane and called "frame base", is defined by the normal (the same as for the previous one), and two orthogonal axes, "width" and "depth", aligned with the sides of the plane. If the plane has not the shape of a box, this reference frame is not available. This coordinate system is also positive defined. These components are all measured in centimeters.

Definition at line 67 of file PlaneGeo.h.

Member Typedef Documentation

Type returned by IterateElements().

Definition at line 74 of file PlaneGeo.h.

using geo::PlaneGeo::GeoNodePath_t = std::vector<TGeoNode const*>

Definition at line 71 of file PlaneGeo.h.

Definition at line 69 of file PlaneGeo.h.

Type of points in the local GDML wire plane frame.

Definition at line 94 of file PlaneGeo.h.

Definition at line 1193 of file PlaneGeo.h.

Type of displacement vectors in the local GDML wire plane frame.

Definition at line 97 of file PlaneGeo.h.

Type for description of rectangles.

Definition at line 144 of file PlaneGeo.h.

Type describing a 3D point or vector decomposed on a plane with plane frame base (width and depth).

Definition at line 139 of file PlaneGeo.h.

Type used for plane decompositions on plane frame (width/depth).

Definition at line 135 of file PlaneGeo.h.

using geo::PlaneGeo::WidthDepthDisplacement_t = ROOT::Math::DisplacementVector2D<ROOT::Math::Cartesian2D<double>, WidthDepthReferenceTag>

Type for vector projections in the plane frame base representation.

Definition at line 132 of file PlaneGeo.h.

using geo::PlaneGeo::WidthDepthProjection_t = ROOT::Math::DisplacementVector2D<ROOT::Math::Cartesian2D<double>, WidthDepthReferenceTag>

Type for projections in the plane frame base representation.

Todo:
the following should be a PositionVector2D

Definition at line 128 of file PlaneGeo.h.

Definition at line 70 of file PlaneGeo.h.

using geo::PlaneGeo::WireCoordProjection_t = ROOT::Math::DisplacementVector2D<ROOT::Math::Cartesian2D<double>, WireCoordinateReferenceTag>

Type for projections in the wire base representation.

Definition at line 109 of file PlaneGeo.h.

Type describing a 3D point or vector decomposed on a plane on wire base.

Definition at line 115 of file PlaneGeo.h.

Type used for plane decompositions on wire base.

Definition at line 112 of file PlaneGeo.h.

Constructor & Destructor Documentation

geo::PlaneGeo::PlaneGeo ( TGeoNode const *  node,
TransformationMatrix &&  trans,
WireCollection_t &&  wires 
)

Construct a representation of a single plane of the detector.

Definition at line 353 of file PlaneGeo.cxx.

References DetectGeometryDirections(), fNode, and UpdateWirePitchSlow().

354  : fNode(node), fTrans(std::move(trans)), fWire(std::move(wires))
355  {
356  if (!fNode->GetVolume()) {
357  throw cet::exception("PlaneGeo")
358  << "Plane geometry node " << fNode->IsA()->GetName() << "[" << fNode->GetName() << ", #"
359  << fNode->GetNumber() << "] has no volume!\n";
360  }
361 
362  // view is now set at TPC level with SetView
363 
366  }
TGeoNode const * fNode
Node within full geometry.
Definition: PlaneGeo.h:1205
void DetectGeometryDirections()
Sets the geometry directions.
Definition: PlaneGeo.cxx:609
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
void UpdateWirePitchSlow()
Updates the stored wire pitch with a slower, more robust algorithm.
Definition: PlaneGeo.cxx:890
LocalTransformation_t fTrans
Plane to world transform.
Definition: PlaneGeo.h:1206
cet::coded_exception< error, detail::translate > exception
Definition: exception.h:33

Member Function Documentation

Rect const& geo::PlaneGeo::ActiveArea ( ) const
inline

Returns an area covered by the wires in the plane.

The precise definition of the area is not specified, therefore this area should not be used for physics.

The current implementation is documented in the source file.

Definition at line 597 of file PlaneGeo.h.

References fActiveArea, art::detail::indent(), PlaneInfo(), and PrintPlaneInfo().

Referenced by PrintPlaneInfo().

597 { return fActiveArea; }
Rect fActiveArea
Area covered by wires in frame base.
Definition: PlaneGeo.h:1225
BoxBoundedGeo geo::PlaneGeo::BoundingBox ( ) const

Returns the world coordinates of the box containing the plane.

See also
GetBoxCenter()

Definition at line 370 of file PlaneGeo.cxx.

References geo::BoxBoundedGeo::ExtendToInclude(), geo::BoxBoundedGeo::SetBoundaries(), toWorldCoords(), and Volume().

Referenced by Depth(), and PrintPlaneInfo().

371  {
372  //
373  // The algorithm is not very refined...
374  //
375 
376  TGeoBBox const* pShape = dynamic_cast<TGeoBBox const*>(Volume().GetShape());
377  if (!pShape) {
378  throw cet::exception("PlaneGeo")
379  << "BoundingBox(): volume " << Volume().IsA()->GetName() << " is not a TGeoBBox!";
380  }
381 
382  BoxBoundedGeo box;
383  unsigned int points = 0;
384  for (double dx : {-(pShape->GetDX()), +(pShape->GetDX())}) {
385  for (double dy : {-(pShape->GetDY()), +(pShape->GetDY())}) {
386  for (double dz : {-(pShape->GetDZ()), +(pShape->GetDZ())}) {
387 
388  auto const p = toWorldCoords(LocalPoint_t{dx, dy, dz});
389 
390  if (points++ == 0)
391  box.SetBoundaries(p, p);
392  else
393  box.ExtendToInclude(p);
394 
395  } // for z
396  } // for y
397  } // for x
398  return box;
399  }
TGeoVolume const & Volume() const
Definition: PlaneGeo.h:1145
Point_t toWorldCoords(LocalPoint_t const &local) const
Transform point from local plane frame to world frame.
Definition: PlaneGeo.h:1111
A base class aware of world box coordinatesAn object describing a simple shape can inherit from this ...
Definition: BoxBoundedGeo.h:31
void SetBoundaries(Coord_t x_min, Coord_t x_max, Coord_t y_min, Coord_t y_max, Coord_t z_min, Coord_t z_max)
Sets the boundaries in world coordinates as specified.
void ExtendToInclude(Coord_t x, Coord_t y, Coord_t z)
Extends the current box to also include the specified point.
Point3DBase_t< PlaneGeoCoordinatesTag > LocalPoint_t
Type of points in the local GDML wire plane frame.
Definition: PlaneGeo.h:94
cet::coded_exception< error, detail::translate > exception
Definition: exception.h:33
geo::WireID geo::PlaneGeo::ClosestWireID ( WireID::WireID_t  wireNo) const
inline

Returns the closest valid wire ID to the specified wire.

Parameters
wireNonumber of the wire on this plane
Returns
complete wire ID of the closest wire on this plane

If the wire number described a wire present on this plane, its complete wire ID is returned, valid. Otherwise, a valid wire ID is returned which points to the existing wire closest to the specified wire number: the first wire if the wire number is negative, or the last wire if the wire number is larger than the actual wires.

Note that the argument geo::WireID::WireID_t type is an integral type, and if a floating point value is specified for it, it's subject to truncation.

Definition at line 1243 of file PlaneGeo.h.

References ID(), and Nwires().

Referenced by ClosestWireID(), GetWireDirection(), and NearestWire().

1244 {
1245  return {ID(), std::min(wireNo, Nwires())};
1246 }
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
PlaneID const & ID() const
Returns the identifier of this plane.
Definition: PlaneGeo.h:173
geo::WireID geo::PlaneGeo::ClosestWireID ( WireID const &  wireid) const
inline

Returns the closest valid wire ID to the specified wire.

Parameters
wireidthe wire ID (must be on this plane)
Returns
complete wire ID of the closest wire, invalid if not this plane
See also
ClosestWireID(geo::WireID::WireID_t)

If wireid is not on this plane, it is returned but marked as invalid. Otherwise, the returned ID is the same as in ClosestWireID(geo::WireID::WireID_t).

Definition at line 1248 of file PlaneGeo.h.

References geo::WireID::asPlaneID(), ClosestWireID(), ID(), and geo::WireID::Wire.

1249 {
1250  if (wireid.asPlaneID() != ID()) { return {}; }
1251  return ClosestWireID(wireid.Wire);
1252 }
WireID ClosestWireID(WireID::WireID_t wireNo) const
Returns the closest valid wire ID to the specified wire.
Definition: PlaneGeo.h:1243
PlaneID const & ID() const
Returns the identifier of this plane.
Definition: PlaneGeo.h:173
Point_t geo::PlaneGeo::ComposePoint ( WireDecomposedVector_t const &  decomp) const
inline

Returns the 3D point from composition of projection and distance.

Parameters
decompdecomposed point
Returns
the 3D point from composition of projection and distance
See also
DecomposePoint(), ComposePoint(double, WireCoordProjection_t const&)

See ComposePoint(double, WireCoordProjection_t const&) for details.

Definition at line 824 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposePoint(), and fDecompWire.

Referenced by larg4::LArVoxelReadout::RecoverOffPlaneDeposit().

825  {
826  return fDecompWire.ComposePoint(decomp);
827  }
Point_t ComposePoint(DecomposedVector_t const &decomp) const
Returns the 3D point from composition of projection and distance.
Definition: Decomposer.h:605
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Point_t geo::PlaneGeo::ComposePoint ( double  distance,
WireCoordProjection_t const &  proj 
) const
inline

Returns the 3D point from composition of projection and distance.

Parameters
distancedistance of the target point from the wire plane
projprojection of the target point on the wire plane
Returns
the 3D point from composition of projection and distance
See also
DecomposePoint()

The returned point is the reference point of the frame system (that is, the plane center), translated by two 3D vectors:

  1. a vector parallel to the plane normal, with norm the input distance
  2. a vector lying on the plane, whose projection via PointProjection() gives the input projection

The choice of the projection reference point embodies the same convention used in PointProjection() and DecomposePoint(). In fact, the strict definition of the result of this method is a 3D point whose decomposition on the plane frame base matches the method arguments.

Definition at line 850 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposePoint(), and fDecompWire.

851  {
852  return fDecompWire.ComposePoint(distance, proj);
853  }
Point_t ComposePoint(DecomposedVector_t const &decomp) const
Returns the 3D point from composition of projection and distance.
Definition: Decomposer.h:605
Float_t proj
Definition: plot.C:35
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Point_t geo::PlaneGeo::ComposePoint ( WDDecomposedVector_t const &  decomp) const
inline

Returns the 3D vector from composition of projection and distance.

Parameters
decompdecomposed point
Returns
the 3D vector from composition of projection and distance
See also
DecomposePointWidthDepth(), ComposePointWidthDepth(double, DecomposedVector_t::Projection_t const&)

See ComposePointWidthDepth(double, DecomposedVector_t::Projection_t const&) for details.

Definition at line 1069 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposePoint(), and fDecompFrame.

1070  {
1071  return fDecompFrame.ComposePoint(decomp);
1072  }
Point_t ComposePoint(DecomposedVector_t const &decomp) const
Returns the 3D point from composition of projection and distance.
Definition: Decomposer.h:605
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Point_t geo::PlaneGeo::ComposePoint ( double  distance,
WidthDepthProjection_t const &  proj 
) const
inline

Returns the 3D point from composition of projection and distance.

Parameters
distancedistance of the target point from the wire plane
projprojection of the target point on the wire plane
Returns
the 3D vector from composition of projection and distance
See also
DecomposePointWidthDepth()

The returned vector is the sum of two 3D vectors:

  1. a vector parallel to the plane normal, with norm the input distance
  2. a vector lying on the plane, whose projection via PointWidthDepthProjection() gives the input projection

Given the arbitrary definition of the projection reference, it is assumed that the same convention is used as in PointWidthDepthProjection() and DecomposePointWidthDepth().

Definition at line 1093 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposePoint(), fDecompFrame, fTrans, geo::LocalTransformationGeo< StoredMatrix, LocalPoint, LocalVector >::toWorldCoords(), and toWorldCoords().

1094  {
1095  return fDecompFrame.ComposePoint(distance, proj);
1096  }
Point_t ComposePoint(DecomposedVector_t const &decomp) const
Returns the 3D point from composition of projection and distance.
Definition: Decomposer.h:605
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Float_t proj
Definition: plot.C:35
Vector_t geo::PlaneGeo::ComposeVector ( WireDecomposedVector_t const &  decomp) const
inline

Returns the 3D vector from composition of projection and distance.

Parameters
decompdecomposed vector
Returns
the 3D vector from composition of projection and distance
See also
DecomposePoint(), ComposeVector(double, WireCoordProjection_t const&), ComposePoint(WireDecomposedVector_t const&)

See ComposeVector(double, WireCoordProjection_t const&) for details.

Definition at line 790 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposeVector(), and fDecompWire.

791  {
792  return fDecompWire.ComposeVector(decomp);
793  } //@}
Vector_t ComposeVector(DecomposedVector_t const &decomp) const
Returns the 3D vector from composition of projection and distance.
Definition: Decomposer.h:646
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Vector_t geo::PlaneGeo::ComposeVector ( double  distance,
WireCoordProjection_t const &  proj 
) const
inline

Returns the 3D vector from composition of projection and distance.

Parameters
distancecomponent of target vector orthogonal to the wire plane
projprojection of the target vector on the wire plane
Returns
the 3D vector from composition of projection and distance
See also
DecomposePoint()

The returned vector is the sum of two 3D vectors:

  1. a vector parallel to the plane normal, with norm the input distance
  2. a vector lying on the plane, whose projection via VectorProjection() gives the input projection

Definition at line 809 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::ComposeVector(), and fDecompWire.

810  {
811  return fDecompWire.ComposeVector(distance, proj);
812  }
Vector_t ComposeVector(DecomposedVector_t const &decomp) const
Returns the 3D vector from composition of projection and distance.
Definition: Decomposer.h:646
Float_t proj
Definition: plot.C:35
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
double geo::PlaneGeo::CosPhiZ ( ) const
inline

Cosine of PhiZ()

Definition at line 170 of file PlaneGeo.h.

References fCosPhiZ.

170 { return fCosPhiZ; }
double fCosPhiZ
Cosine of .
Definition: PlaneGeo.h:1212
WireDecomposedVector_t geo::PlaneGeo::DecomposePoint ( Point_t const &  point) const
inline

Decomposes a 3D point in two components.

Parameters
pointthe point to be decomposed
Returns
the two components of point, on the plane and orthogonal to it

The point is decomposed in:

  1. a component orthogonal to the plane, expressed as a signed real number
  2. a component lying on the plane, expressed as a 2D vector

The distance is obtained as by DistanceFromPlane(). The projection on the plane is obtained following the same convention as PointProjection().

Definition at line 723 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::DecomposePoint(), and fDecompWire.

724  {
725  return fDecompWire.DecomposePoint(point);
726  }
DecomposedVector_t DecomposePoint(Point_t const &point) const
Decomposes a 3D point in two components.
Definition: Decomposer.h:511
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
WDDecomposedVector_t geo::PlaneGeo::DecomposePointWidthDepth ( Point_t const &  point) const
inline

Decomposes a 3D point in two components.

Parameters
pointthe point to be decomposed
Returns
the two components of point, on the plane and orthogonal to it

The point is decomposed in:

  1. a component orthogonal to the plane, expressed as a signed real number
  2. a component lying on the plane, expressed as a 2D vector

The distance is obtained as by DistanceFromPlane(). The projection on the plane is obtained following the same convention as PointWidthDepthProjection().

Definition at line 880 of file PlaneGeo.h.

References geo::Decomposer< Vector, Point, ProjVector >::DecomposePoint(), and fDecompFrame.

881  {
882  return fDecompFrame.DecomposePoint(point);
883  }
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
DecomposedVector_t DecomposePoint(Point_t const &point) const
Decomposes a 3D point in two components.
Definition: Decomposer.h:511
PlaneGeo::WidthDepthProjection_t geo::PlaneGeo::DeltaFromActivePlane ( WidthDepthProjection_t const &  proj,
double  wMargin,
double  dMargin 
) const

Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the active area of plane.

Parameters
projstarting projection
wMarginthe point is brought this amount inside the active area
dMarginthe point is brought this amount inside the active area
Returns
a projection displacement
See also
DeltaFromPlane()

The "active" area of the plane is the rectangular area which includes all the wires. The area is obtained as the smallest rectangle including the projection of both ends of all wires in the plane, less half a pitch. This defines a "fiducial" area away from the borders of the plane. The projection is in the frame reference (PointWidthDepthProjection()). The area is reduced on each side by the specified margins. If for example wMargin is 1.0, the active area lower border on the width direction will be increased by 1 cm, and the upper border will be decreased by 1 cm effectively making the active area 2 cm narrowed on the width direction. The same independently applies to the depth direction with dMargin. The main purpose of the margins is to accommodate for rounding errors. A version of this method with default margins of 0 is also available.

If the projection is already on the active area of the plane, the returned displacement is null. Otherwise, the displacement, added to proj, will bring it on the active plane area (in fact, on its border).

Definition at line 440 of file PlaneGeo.cxx.

References lar::util::simple_geo::Range< Data >::delta(), lar::util::simple_geo::Rectangle< Data >::depth, fActiveArea, and lar::util::simple_geo::Rectangle< Data >::width.

Referenced by DeltaFromActivePlane(), DeltaFromPlane(), and larg4::LArVoxelReadout::RecoverOffPlaneDeposit().

444  {
445  return {fActiveArea.width.delta(proj.X(), wMargin), fActiveArea.depth.delta(proj.Y(), dMargin)};
446  }
Rect fActiveArea
Area covered by wires in frame base.
Definition: PlaneGeo.h:1225
Range_t width
Range along width direction.
Definition: SimpleGeo.h:428
Range_t depth
Range along depth direction.
Definition: SimpleGeo.h:429
Data_t delta(Data_t v, Data_t margin=0.0) const
Definition: SimpleGeo.h:472
Float_t proj
Definition: plot.C:35
WidthDepthProjection_t geo::PlaneGeo::DeltaFromActivePlane ( WidthDepthProjection_t const &  proj,
double  margin = 0.0 
) const
inline

Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the active area of plane.

Parameters
projstarting projection
marginthe point is brought this amount inside the active area _(default: 0)_
Returns
a projection displacement
See also
DeltaFromActivePlane(WidthDepthProjection_t const&, double, double)

This is the implementation with default values for margins of DeltaFromActivePlane(). The depth and width margins are the same, and 0 by default.

Definition at line 1021 of file PlaneGeo.h.

References DeltaFromActivePlane(), MovePointOverPlane(), and MoveProjectionToPlane().

1023  {
1024  return DeltaFromActivePlane(proj, margin, margin);
1025  }
WidthDepthProjection_t DeltaFromActivePlane(WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
Returns a projection vector that, added to the argument, gives a projection inside (or at the border ...
Definition: PlaneGeo.cxx:440
Float_t proj
Definition: plot.C:35
PlaneGeo::WidthDepthProjection_t geo::PlaneGeo::DeltaFromPlane ( WidthDepthProjection_t const &  proj,
double  wMargin,
double  dMargin 
) const

Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the plane.

Parameters
projstarting projection
wMarginthe point is brought this amount inside the target area
dMarginthe point is brought this amount inside the target area
Returns
a projection displacement
See also
DeltaFromActivePlane()

The returned projection vector is guaranteed, when added to proj, to yield a projection on or within the border of the plane (the "target area"), as defined by the GDML geometry.

The target plane area is reduced on each side by the specified margins. If for example wMargin is 1.0, the area lower border on the width direction will be increased by 1 cm, and the upper border will be decreased by 1 cm effectively making the area 2 cm narrowed on the width direction. The same independently applies to the depth direction with dMargin. The main purpose of the margins is to accommodate for rounding errors. A version of this method with default margins of 0 is also available.

If the projection is already on the target area, the returned displacement is null.

Definition at line 431 of file PlaneGeo.cxx.

References fFrameSize, geo::PlaneGeo::RectSpecs::HalfDepth(), and geo::PlaneGeo::RectSpecs::HalfWidth().

Referenced by DeltaFromPlane(), isProjectionOnPlane(), MovePointOverPlane(), MoveProjectionToPlane(), and VectorWidthDepthProjection().

434  {
435  return {symmetricCapDelta(proj.X(), fFrameSize.HalfWidth() - wMargin),
436  symmetricCapDelta(proj.Y(), fFrameSize.HalfDepth() - dMargin)};
437  }
double HalfWidth() const
Definition: PlaneGeo.h:1199
RectSpecs fFrameSize
Definition: PlaneGeo.h:1223
double HalfDepth() const
Definition: PlaneGeo.h:1200
Float_t proj
Definition: plot.C:35
WidthDepthProjection_t geo::PlaneGeo::DeltaFromPlane ( WidthDepthProjection_t const &  proj,
double  margin = 0.0 
) const
inline

Returns a projection vector that, added to the argument, gives a projection inside (or at the border of) the area of plane.

Parameters
projstarting projection
marginthe point is brought this amount inside the plane area _(default: 0)_
Returns
a projection displacement
See also
DeltaFromPlane(WidthDepthProjection_t const&, double, double)

This is the implementation with default values for margins of DeltaFromPlane(). The depth and width margins are the same, and 0 by default.

Definition at line 973 of file PlaneGeo.h.

References DeltaFromActivePlane(), and DeltaFromPlane().

975  {
976  return DeltaFromPlane(proj, margin, margin);
977  }
WidthDepthProjection_t DeltaFromPlane(WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
Returns a projection vector that, added to the argument, gives a projection inside (or at the border ...
Definition: PlaneGeo.cxx:431
Float_t proj
Definition: plot.C:35
double geo::PlaneGeo::Depth ( ) const
inline

Return the depth of the plane.

See also
Width(), WidthDir(), DepthDir()

The precise definition is arbitrary (see DepthDir()).

Definition at line 218 of file PlaneGeo.h.

References BoundingBox(), geo::PlaneGeo::RectSpecs::Depth(), fFrameSize, fWire, and Nwires().

Referenced by PrintPlaneInfo().

218 { return fFrameSize.Depth(); }
double Depth() const
Definition: PlaneGeo.h:1202
RectSpecs fFrameSize
Definition: PlaneGeo.h:1223
Vector_t const& geo::PlaneGeo::DepthDir ( ) const
inline

Return the direction of plane depth.

The precise definition of the sides is arbitrary, but they are defined to lie on the wire plane and so that WidthDir(), DepthDir() and GetNormalDirection() make a orthonormal base. That base (width, depth, normal) is guaranteed to be positive defined.

Definition at line 201 of file PlaneGeo.h.

References fDecompFrame, and geo::Decomposer< Vector, Point, ProjVector >::SecondaryDir().

Referenced by MovePointOverPlane(), PrintPlaneInfo(), and UpdateWidthDepthDir().

201 { return fDecompFrame.SecondaryDir(); }
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Vector_t const & SecondaryDir() const
Returns the plane secondary axis direction.
Definition: Decomposer.h:453
void geo::PlaneGeo::DetectGeometryDirections ( )
private

Sets the geometry directions.

Definition at line 609 of file PlaneGeo.cxx.

References util::abs(), e, fDecompFrame, fFrameSize, geo::PlaneGeo::RectSpecs::halfDepth, geo::PlaneGeo::RectSpecs::halfWidth, geo::origin(), geo::vect::rounded01(), geo::Decomposer< Vector, Point, ProjVector >::SetMainDir(), geo::Decomposer< Vector, Point, ProjVector >::SetOrigin(), geo::Decomposer< Vector, Point, ProjVector >::SetSecondaryDir(), toWorldCoords(), Volume(), and geo::Z.

Referenced by PlaneGeo(), and Volume().

610  {
611  // We need to identify which are the "long" directions of the plane. We assume it is
612  // a box, and the shortest side is excluded. The first direction ("width") is given
613  // by preference to z. If z is the direction of the normal to the plane... oh well.
614  // Let's say privilege to the one which comes from local z, then y. That means:
615  // undefined.
616  //
617  // Requirements:
618  // - ROOT geometry information (shapes and transformations)
619  // - the shape must be a box (an error is PRINTED if not)
620  // - center of the wire plane (not just the center of the plane box)
621 
622  // how do they look like in the world?
623  TGeoBBox const* pShape = dynamic_cast<TGeoBBox const*>(Volume().GetShape());
624  if (!pShape) {
625  mf::LogError("BoxInfo") << "Volume " << Volume().IsA()->GetName()
626  << " is not a TGeoBBox! Dimensions won't be available.";
627  // set it invalid
629  fDecompFrame.SetMainDir({0., 0., 0.});
630  fDecompFrame.SetSecondaryDir({0., 0., 0.});
631  fFrameSize = {0.0, 0.0};
632  return;
633  }
634 
635  std::array<Vector_t, 3U> sides;
636  size_t iSmallest = 3;
637  {
638  size_t iSide = 0;
639 
640  sides[iSide] = toWorldCoords(LocalVector_t{pShape->GetDX(), 0.0, 0.0});
641  iSmallest = iSide;
642  ++iSide;
643 
644  sides[iSide] = toWorldCoords(LocalVector_t{0.0, pShape->GetDY(), 0.0});
645  if (sides[iSide].Mag2() < sides[iSmallest].Mag2()) iSmallest = iSide;
646  ++iSide;
647 
648  sides[iSide] = toWorldCoords(LocalVector_t{0.0, 0.0, pShape->GetDZ()});
649  if (sides[iSide].Mag2() < sides[iSmallest].Mag2()) iSmallest = iSide;
650  ++iSide;
651  }
652 
653  // which are the largest ones?
654  size_t kept[2];
655  {
656  size_t iKept = 0;
657  for (size_t i = 0; i < 3; ++i)
658  if (i != iSmallest) kept[iKept++] = i;
659  }
660 
661  // which is which?
662  //
663  // Pick width as the most z-like.
664  size_t const iiWidth =
665  std::abs(sides[kept[0]].Unit().Z()) > std::abs(sides[kept[1]].Unit().Z()) ? 0 : 1;
666  size_t const iWidth = kept[iiWidth];
667  size_t const iDepth = kept[1 - iiWidth]; // the other
668 
669  fDecompFrame.SetMainDir(vect::rounded01(sides[iWidth].Unit(), 1e-4));
670  fDecompFrame.SetSecondaryDir(vect::rounded01(sides[iDepth].Unit(), 1e-4));
671  fFrameSize.halfWidth = sides[iWidth].R();
672  fFrameSize.halfDepth = sides[iDepth].R();
673  }
TGeoVolume const & Volume() const
Definition: PlaneGeo.h:1145
void SetSecondaryDir(Vector_t const &dir)
Change the secondary direction of the projection base.
Definition: Decomposer.h:436
constexpr auto abs(T v)
Returns the absolute value of the argument.
Point_t toWorldCoords(LocalPoint_t const &local) const
Transform point from local plane frame to world frame.
Definition: PlaneGeo.h:1111
MaybeLogger_< ELseverityLevel::ELsev_error, false > LogError
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
RectSpecs fFrameSize
Definition: PlaneGeo.h:1223
Vector rounded01(Vector const &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
void SetOrigin(Point_t const &point)
Change the 3D point of the reference frame origin.
Definition: Decomposer.h:430
Vector3DBase_t< PlaneGeoCoordinatesTag > LocalVector_t
Type of displacement vectors in the local GDML wire plane frame.
Definition: PlaneGeo.h:97
Float_t e
Definition: plot.C:35
constexpr Point origin()
Returns a origin position with a point of the specified type.
Definition: geo_vectors.h:229
void SetMainDir(Vector_t const &dir)
Change the main direction of the projection base.
Definition: Decomposer.h:433
double geo::PlaneGeo::DistanceFromPlane ( Point_t const &  point) const
inline

Returns the distance of the specified point from the wire plane.

Parameters
pointa point in world coordinates [cm]
Returns
the signed distance from the wire plane

The distance is defined positive if the point lies in the side the normal vector (GetNormalDirection()) points to.

The distance is defined from the geometric plane where the wires lie, and it may not match the distance from the center of the geometry box representing the plane. It should always match the drift distance from this wire plane, and the result of DriftPoint(point, DistanceFromPlane(point)) will bring the point to the plane.

Definition at line 484 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::PointNormalComponent().

Referenced by DriftPoint(), larg4::LArVoxelReadout::RecoverOffPlaneDeposit(), and UpdateWirePlaneCenter().

485  {
486  return fDecompWire.PointNormalComponent(point);
487  }
auto PointNormalComponent(Point_t const &point) const
Returns the secondary component of a point.
Definition: Decomposer.h:476
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
void geo::PlaneGeo::DriftPoint ( Point_t position,
double  distance 
) const
inline

Shifts the position of an electron drifted by a distance.

Parameters
position_(modified)_ the position of the electron
distancedrift distance to shift the electron by [cm]

This is a pure geometry computation: the position is shifted by the drift distance in the direction opposite to the normal to the plane (as returned by GetNormalDirection()), no matter where the position is relative to the plane. The wording about "electron position" is just meant to remind that the drift shift is taken with opposite sign: since the point is assumed to be an electron, a positive drift normally moves its position toward the wire plane.

Definition at line 503 of file PlaneGeo.h.

References GetNormalDirection().

Referenced by UpdateWirePlaneCenter().

504  {
505  position -= distance * GetNormalDirection();
506  }
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
void geo::PlaneGeo::DriftPoint ( Point_t position) const
inline

Shifts the position along drift direction to fall on the plane.

Parameters
position_(modified)_ the position to be shifted

This is a pure geometry computation: the position is shifted by the drift distance in the direction opposite to the normal to the plane (as returned by GetNormalDirection()), no matter where the position is relative to the plane.

Definition at line 518 of file PlaneGeo.h.

References dir, DistanceFromPlane(), DriftPoint(), InterWireDistance(), and InterWireProjectedDistance().

Referenced by DriftPoint().

518 { DriftPoint(position, DistanceFromPlane(position)); }
double DistanceFromPlane(Point_t const &point) const
Returns the distance of the specified point from the wire plane.
Definition: PlaneGeo.h:484
void DriftPoint(Point_t &position, double distance) const
Shifts the position of an electron drifted by a distance.
Definition: PlaneGeo.h:503
WireGeo const& geo::PlaneGeo::FirstWire ( ) const
inline

Return the first wire in the plane.

Definition at line 298 of file PlaneGeo.h.

References Wire().

Referenced by ThetaZ(), UpdateDecompWireOrigin(), and UpdateWireDir().

298 { return Wire(0); }
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
Point_t geo::PlaneGeo::GetBoxCenter ( ) const
inline

Returns the centre of the box representing the plane.

Returns
the centre of the box, in world coordinates [cm]
See also
GetCenter()

This is the centre of the box representing the plane in the geometry description, in world coordinates. This is rarely of any use, as most of the times GetCenter() delivers the proper information, e.g. for simulation and reconstruction.

Definition at line 380 of file PlaneGeo.h.

References toWorldCoords().

Referenced by geo::GeometryBuilderStandard::makeTPC(), UpdatePlaneNormal(), and UpdateWirePlaneCenter().

380 { return toWorldCoords(LocalPoint_t{0.0, 0.0, 0.0}); }
Point_t toWorldCoords(LocalPoint_t const &local) const
Transform point from local plane frame to world frame.
Definition: PlaneGeo.h:1111
Point3DBase_t< PlaneGeoCoordinatesTag > LocalPoint_t
Type of points in the local GDML wire plane frame.
Definition: PlaneGeo.h:94
Point_t const& geo::PlaneGeo::GetCenter ( ) const
inline

Returns the centre of the wire plane in world coordinates [cm].

See also
GetBoxCenter()

The center of the plane is defined so that it has width and depth coordinates in the middle of the plane box (that is, the geometrical representation of the plane in the geometry description), and the other coordinate set at drift distance 0.

Note that this does not necessarily match the center of the box, if the geometry does not place the wires, which define the drift distance, in the plane in the middle of the box.

Definition at line 366 of file PlaneGeo.h.

References fCenter.

Referenced by larg4::LArVoxelReadout::DriftIonizationElectrons(), PrintPlaneInfo(), DUNE::NeutrinoTrackingEff::truthLength(), and UpdateDecompWireOrigin().

366 { return fCenter; }
Point_t fCenter
Center of the plane, lying on the wire plane.
Definition: PlaneGeo.h:1227
WireGeo const& geo::PlaneGeo::GetElement ( WireID const &  wireid) const
inline

Returns the wire in wireid from this plane.

Parameters
wireidfull wire ID
Returns
a constant reference to the wire in wireid
Exceptions
cet::exception(category "WireOutOfRange") if no such wire

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 274 of file PlaneGeo.h.

References Wire().

274 { return Wire(wireid); }
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
auto geo::PlaneGeo::GetElementPtr ( WireID const &  wireid) const
inline

Returns the wire in wireid from this plane.

Parameters
wireidfull wire ID
Returns
a constant pointer to the wire, or nullptr if it does not exist

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 294 of file PlaneGeo.h.

References WirePtr().

294 { return WirePtr(wireid); }
auto WirePtr(unsigned int iwire) const
Returns the wire number iwire from this plane.
Definition: PlaneGeo.h:282
Vector_t const& geo::PlaneGeo::GetIncreasingWireDirection ( ) const
inline

Returns the direction of increasing wires.

Returns
a TVector3 versor with the direction of increasing wires

The versor is orthogonal to the wires (assumed parallel), lies on the plane and its direction goes toward increasing wire IDs.

Definition at line 350 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::SecondaryDir().

Referenced by ShowerRecoTools::ShowerTrajPointdEdx::CalculateElement(), PrintPlaneInfo(), shouldFlipWire(), UpdatePhiZ(), and WireIDincreasesWithZ().

350 { return fDecompWire.SecondaryDir(); }
Vector_t const & SecondaryDir() const
Returns the plane secondary axis direction.
Definition: Decomposer.h:453
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Vector_t geo::PlaneGeo::GetNormalAxis ( ) const
private

Returns a direction normal to the plane (pointing is not defined).

Definition at line 676 of file PlaneGeo.cxx.

References geo::WireGeo::Direction(), e, geo::WireGeo::GetCenter(), Nwires(), geo::vect::rounded01(), and Wire().

Referenced by UpdatePlaneNormal(), and Volume().

677  {
678  unsigned const int NWires = Nwires();
679  if (NWires < 2) return {}; // why are we even here?
680 
681  // 1) get the direction of the middle wire
682  auto const WireDir = Wire(NWires / 2).Direction();
683 
684  // 2) get the direction between the middle wire and the next one
685  auto const ToNextWire = Wire(NWires / 2 + 1).GetCenter() - Wire(NWires / 2).GetCenter();
686 
687  // 3) get the direction perpendicular to the plane
688  // 4) round it
689  // 5) return its norm
690  return vect::rounded01(WireDir.Cross(ToNextWire).Unit(), 1e-4);
691  }
Point_t const & GetCenter() const
Returns the world coordinate of the center of the wire [cm].
Definition: WireGeo.h:219
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
Vector_t Direction() const
Definition: WireGeo.h:287
Vector rounded01(Vector const &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
Float_t e
Definition: plot.C:35
Vector_t const& geo::PlaneGeo::GetNormalDirection ( ) const
inline

Returns the direction normal to the plane.

Returns
a TVector3 versor with a direction normal to the plane

The versor is orthogonal to the plane. The direction is defined so that the semi-space pointed to contains the TPC center.

Note
Each decomposition base (wire-based and frame-based) has its own normal, defined solely from its two decomposition plane axes. The wire-based frame is nevertheless required to have a normal matching this one, while the frame-based normal might happen to be in the opposite direction depending on the original geometry description.

Definition at line 339 of file PlaneGeo.h.

References fNormal.

Referenced by DriftPoint(), PrintPlaneInfo(), shouldFlipWire(), UpdateIncreasingWireDir(), UpdateOrientation(), UpdateView(), UpdateWidthDepthDir(), and UpdateWireDir().

339 { return fNormal; }
Vector_t fNormal
Definition: PlaneGeo.h:1214
Vector_t const& geo::PlaneGeo::GetWireDirection ( ) const
inline

Returns the direction of the wires.

Returns
a unit vector following the direction of the wires

All wires in the plane are assumed parallel.

Definition at line 390 of file PlaneGeo.h.

References ClosestWireID(), fDecompWire, geo::Decomposer< Vector, Point, ProjVector >::MainDir(), NearestWire(), and NearestWireID().

Referenced by PrintPlaneInfo(), lar::util::TrackPitchInView(), and UpdateView().

390 { return fDecompWire.MainDir(); }
Vector_t const & MainDir() const
Returns the plane main axis direction.
Definition: Decomposer.h:450
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
bool geo::PlaneGeo::HasElement ( unsigned int  iwire) const
inline

Returns whether a wire with index iwire is present in this plane.

Parameters
iwireindex of wire in this plane
Returns
whether the wire with index iwire is present in this plane

Definition at line 242 of file PlaneGeo.h.

References HasWire().

242 { return HasWire(iwire); }
bool HasWire(unsigned int iwire) const
Returns whether a wire with index iwire is present in this plane.
Definition: PlaneGeo.h:241
bool geo::PlaneGeo::HasElement ( WireID const &  wireid) const
inline

Returns whether the wire in wireid is present in this plane.

Parameters
wireidfull wire ID
Returns
whether the wire in wireid is present in this plane

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 255 of file PlaneGeo.h.

References HasWire(), and Wire().

255 { return HasWire(wireid); }
bool HasWire(unsigned int iwire) const
Returns whether a wire with index iwire is present in this plane.
Definition: PlaneGeo.h:241
bool geo::PlaneGeo::HasWire ( unsigned int  iwire) const
inline

Returns whether a wire with index iwire is present in this plane.

Parameters
iwireindex of wire in this plane
Returns
whether the wire with index iwire is present in this plane

Definition at line 241 of file PlaneGeo.h.

References Nwires().

Referenced by HasElement(), geo::WireReadoutGeom::HasWire(), and WirePtr().

241 { return iwire < Nwires(); }
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
bool geo::PlaneGeo::HasWire ( WireID const &  wireid) const
inline

Returns whether the wire in wireid is present in this plane.

Parameters
wireidfull wire ID
Returns
whether the wire in wireid is present in this plane

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 254 of file PlaneGeo.h.

References HasWire(), and geo::WireID::Wire.

Referenced by HasWire().

254 { return HasWire(wireid.Wire); }
bool HasWire(unsigned int iwire) const
Returns whether a wire with index iwire is present in this plane.
Definition: PlaneGeo.h:241
PlaneID const& geo::PlaneGeo::ID ( ) const
inline

Returns the identifier of this plane.

Definition at line 173 of file PlaneGeo.h.

References fID.

Referenced by ClosestWireID(), detinfo::DetectorPropertiesStandard::DataFor(), geo::WireReadoutDumper::dumpTPCplane(), NearestWire(), NearestWireID(), PrintPlaneInfo(), and lar::util::TrackPitchInView().

173 { return fID; }
PlaneID fID
ID of this plane.
Definition: PlaneGeo.h:1229
double geo::PlaneGeo::InterWireDistance ( Vector_t const &  dir) const

Returns the distance between wires along the specified direction.

Parameters
dirthe direction (3D)
Returns
the distance between wires along that direction [cm]

The direction is specified as a 3D vector in the world coordinate frame. The modulus of the vector is ignored but expected to be non null.

The returned distance is the space that would be covered starting from a wire toward the dir direction and stopping when the projection on the wire plane reaches another wire. This distance is returned in centimeters, always positive and not smaller than the wire pitch.

Note
If the direction is too close to the wire direction, the result will be numerically unstable and might be infinite (test with std::isinf(), std::isfinite() or std::isnormal()). It is recommended that the caller take special actions when the result is too large.

Definition at line 538 of file PlaneGeo.cxx.

References util::abs(), e, fDecompWire, fWirePitch, r, and geo::Decomposer< Vector, Point, ProjVector >::VectorSecondaryComponent().

Referenced by DriftPoint().

539  {
540  // the secondary component of the wire decomposition basis is wire coord.
541  double const r = dir.R();
542  assert(r >= 1.e-6);
543 
544  double const absWireCoordProj = std::abs(fDecompWire.VectorSecondaryComponent(dir));
545  return r / absWireCoordProj * fWirePitch;
546  }
TRandom r
Definition: spectrum.C:23
auto VectorSecondaryComponent(Vector_t const &v) const
Returns the secondary component of a vector.
Definition: Decomposer.h:525
double fWirePitch
Pitch of wires in this plane.
Definition: PlaneGeo.h:1210
constexpr auto abs(T v)
Returns the absolute value of the argument.
TDirectory * dir
Definition: macro.C:5
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Float_t e
Definition: plot.C:35
double geo::PlaneGeo::InterWireProjectedDistance ( WireCoordProjection_t const &  projDir) const

Returns the distance between wires along the specified direction.

Parameters
projDirthe direction, projected on the plane (2D)
Returns
the distance between wires along that direction [cm]

The direction is specified as a geo::PlaneGeo::WireCoordProjection_t vector, defined as in geo::PlaneGeo::Projection(). The modulus of the projection is ignored but expected to be non null.

The returned distance is the space that would be covered starting from a wire toward the projDir direction and stopping at the first wire met. This distance is returned in centimeters, always positive and not smaller than the wire pitch.

Note
If the direction is too close to the wire direction, the result will be numerically unstable and might be infinite (test with std::isinf(), std::isfinite() or std::isnormal()). It is recommended that the caller take special actions when the result is too large.

Definition at line 531 of file PlaneGeo.cxx.

References e, and fWirePitch.

Referenced by DriftPoint(), and InterWireProjectedDistance().

532  {
533  assert(lar::util::Vector2DComparison{1e-6}.nonZero(projDir));
534  return std::sqrt(cet::square(projDir.X() / projDir.Y()) + 1.0) * fWirePitch;
535  }
double fWirePitch
Pitch of wires in this plane.
Definition: PlaneGeo.h:1210
Class comparing 2D vectors.
Float_t e
Definition: plot.C:35
double geo::PlaneGeo::InterWireProjectedDistance ( Vector_t const &  dir) const
inline

Returns the distance between wires along the specified direction.

Parameters
dirthe direction in detector space (3D)
Returns
the distance between wires along that direction [cm]
See also
InterWireProjectedDistance(geo::PlaneGeo::WireCoordProjection_t const&) const

The direction is specified as a 3D vector. Its modulus is ignored but expected to be non null.

The returned distance is the space that would be covered starting from a wire toward the direction projection of dir on the wire plane, and stopping at the first wire met. This distance is returned in centimeters and always positive.

Note
This is not a 3D distance (for example, it's not useful to compute $ ds $ of a track to get its ionization energy $ dE/ds $), but it is the distance projected on the wire plane.

Definition at line 583 of file PlaneGeo.h.

References InterWireProjectedDistance(), and Projection().

584  {
586  }
double InterWireProjectedDistance(WireCoordProjection_t const &projDir) const
Returns the distance between wires along the specified direction.
Definition: PlaneGeo.cxx:531
TDirectory * dir
Definition: macro.C:5
WireCoordProjection_t Projection(Point_t const &point) const
Returns the projection of the specified point on the plane.
Definition: PlaneGeo.h:755
bool geo::PlaneGeo::isProjectionOnPlane ( Point_t const &  point) const

Returns if the projection of specified point is within the plane.

Parameters
pointworld coordinate of the point to test [cm]
Returns
whether the projection of specified point is within the plane
See also
PointWidthDepthProjection(), Width(), Height()

The method extracts the projection of the specified point on the plane, as in PointWidthDepthProjection(), and then verifies that the projection falls within the wire plane area, as defined by the dimensions from the geometry description.

Definition at line 449 of file PlaneGeo.cxx.

References DeltaFromPlane(), and PointWidthDepthProjection().

Referenced by VectorWidthDepthProjection().

450  {
451  auto const deltaProj = DeltaFromPlane(PointWidthDepthProjection(point));
452  return (deltaProj.X() == 0.) && (deltaProj.Y() == 0.);
453  }
WidthDepthProjection_t PointWidthDepthProjection(Point_t const &point) const
Returns the projection of the specified point on the plane.
Definition: PlaneGeo.h:897
WidthDepthProjection_t DeltaFromPlane(WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
Returns a projection vector that, added to the argument, gives a projection inside (or at the border ...
Definition: PlaneGeo.cxx:431
WireGeo const& geo::PlaneGeo::LastWire ( ) const
inline

Return the last wire in the plane.

Definition at line 304 of file PlaneGeo.h.

References Nwires(), and Wire().

304 { return Wire(Nwires() - 1); }
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
WireGeo const& geo::PlaneGeo::MiddleWire ( ) const
inline

Return the middle wire in the plane.

Definition at line 301 of file PlaneGeo.h.

References Nwires(), and Wire().

301 { return Wire(Nwires() / 2); }
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
Point_t geo::PlaneGeo::MovePointOverPlane ( Point_t const &  point) const

Returns the point, moved so that its projection is over the plane.

Parameters
pointpoint to be checked and moved
Returns
the new value of the point
See also
isProjectionOnPlane(), MoveProjectionToPlane(), Width(), Height()

If the projection of the point on the plane falls outside it, the returned point is translated so that its projection is now on the border of the plane. The translation happens along the directions of the plane frame, as described in MoveProjectionToPlane().

Definition at line 475 of file PlaneGeo.cxx.

References DeltaFromPlane(), DepthDir(), PointWidthDepthProjection(), and WidthDir().

Referenced by DeltaFromActivePlane().

476  {
477  // This implementation is subject to rounding errors, since the result of the addition
478  // might jitter above or below the border.
479 
480  auto const deltaProj = DeltaFromPlane(PointWidthDepthProjection(point));
481  return point + deltaProj.X() * WidthDir() + deltaProj.Y() * DepthDir();
482  }
Vector_t const & DepthDir() const
Return the direction of plane depth.
Definition: PlaneGeo.h:201
WidthDepthProjection_t PointWidthDepthProjection(Point_t const &point) const
Returns the projection of the specified point on the plane.
Definition: PlaneGeo.h:897
WidthDepthProjection_t DeltaFromPlane(WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
Returns a projection vector that, added to the argument, gives a projection inside (or at the border ...
Definition: PlaneGeo.cxx:431
Vector_t const & WidthDir() const
Return the direction of plane width.
Definition: PlaneGeo.h:189
PlaneGeo::WidthDepthProjection_t geo::PlaneGeo::MoveProjectionToPlane ( WidthDepthProjection_t const &  proj) const

Returns the projection, moved onto the plane if necessary.

Parameters
projprojection to be checked and moved
Returns
the new value of the projection
See also
isProjectionOnPlane(), Width(), Height()

The projection proj is defined as in the output of PointWidthDepthProjection(). The method caps width and depth of the projection so that it stays on the plane. A new capped value is returned. Since the reference point of the frame is defined as the center of the plane, this action is equivalent to force the width component in $ \left[ -\frac{w}{2}, \frac{w}{2} \right] $ range and the depth component into $ \left[ -\frac{d}{2}, \frac{d}{2} \right] $, with $ w $ and $ d $ the width and depth of the wire plane.

Definition at line 456 of file PlaneGeo.cxx.

References DeltaFromPlane(), fFrameSize, geo::PlaneGeo::RectSpecs::HalfDepth(), and geo::PlaneGeo::RectSpecs::HalfWidth().

Referenced by DeltaFromActivePlane().

458  {
459  // We have a more complicated implementation to avoid rounding errors. In this way,
460  // the result is really guaranteed to be exactly on the border.
461  auto const delta = DeltaFromPlane(proj);
462  return {(delta.X() == 0.0) ?
463  proj.X() :
464  ((delta.X() > 0) ? -fFrameSize.HalfWidth() // delta positive -> proj on negative side
465  :
467  (delta.Y() == 0.0) ?
468  proj.Y() :
469  ((delta.Y() > 0) ? -fFrameSize.HalfDepth() // delta positive -> proj on negative side
470  :
471  fFrameSize.HalfDepth())};
472  }
double HalfWidth() const
Definition: PlaneGeo.h:1199
RectSpecs fFrameSize
Definition: PlaneGeo.h:1223
double HalfDepth() const
Definition: PlaneGeo.h:1200
WidthDepthProjection_t DeltaFromPlane(WidthDepthProjection_t const &proj, double wMargin, double dMargin) const
Returns a projection vector that, added to the argument, gives a projection inside (or at the border ...
Definition: PlaneGeo.cxx:431
Float_t proj
Definition: plot.C:35
WireGeo const & geo::PlaneGeo::NearestWire ( Point_t const &  pos) const

Returns the wire closest to the specified position.

Parameters
posworld coordinates of the point [cm]
Returns
the ID of the wire closest to the projection of pos on the plane
Exceptions
InvalidWireError(category: "Geometry") if out of range

The position is projected on the wire plane, and the nearest wire to the projected point is returned.

If the wire is father than half a wire pitch from the point, an exception is thrown that contains both the wire that would be the closest one (badWireID()), and also the wire that is actually the closest one (betterWireID()). When this happens, the specified position was outside the wire plane.

Note that the caller should check for containment: this function may or may not report the position being outside the plane, depending on where it is. In the current implementation, the wires are considered infinitely long, and if the position projection is closer than half the wire pitch from any of these extrapolated wires, the method will not report error.

Definition at line 514 of file PlaneGeo.cxx.

References ClosestWireID(), ID(), NearestWireID(), Wire(), and geo::WireID::Wire.

Referenced by GetWireDirection().

515  {
516  // Note that this code is ready for when NearestWireID() will be changed to return an
517  // invalid ID instead of throwing. As things are now, `NearestWireID()` will never
518  // return an invalid ID, but it will throw an exception similar to this one.
519 
520  WireID const wireID = NearestWireID(point);
521  if (wireID) return Wire(wireID); // we have that wire, so we return it
522 
523  // wire ID is invalid, meaning it's out of range. Throw an exception!
524  WireID const closestID = ClosestWireID(wireID);
525  throw InvalidWireError("Geometry", ID(), closestID.Wire, wireID.Wire)
526  << "Can't find nearest wire for position " << point << " in plane " << std::string(ID())
527  << " approx wire number # " << closestID.Wire << " (capped from " << wireID.Wire << ")\n";
528  }
WireID NearestWireID(Point_t const &pos) const
Returns the ID of wire closest to the specified position.
Definition: PlaneGeo.cxx:485
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
WireID_t Wire
Index of the wire within its plane.
Definition: geo_types.h:430
WireID ClosestWireID(WireID::WireID_t wireNo) const
Returns the closest valid wire ID to the specified wire.
Definition: PlaneGeo.h:1243
Exception thrown on invalid wire number.
Definition: Exceptions.h:37
PlaneID const & ID() const
Returns the identifier of this plane.
Definition: PlaneGeo.h:173
WireID geo::PlaneGeo::NearestWireID ( Point_t const &  pos) const

Returns the ID of wire closest to the specified position.

Parameters
posworld coordinates of the point [cm]
Returns
the ID of the wire closest to the projection of pos on the plane
Exceptions
InvalidWireError(category: "Geometry") if out of range

The position is projected on the wire plane, and the ID of the nearest wire to the projected point is returned.

If the wire does not exist, an exception is thrown that contains both the wire that would be the closest one (badWireID()), and also the wire that is actually the closest one (betterWireID()). When this happens, the specified position was outside the wire plane.

Note that the caller should check for containment: this function may or may not report the position being outside the plane, depending on where it is. In the current implementation, the wires are considered infinitely long, and if the position projection is closer than half the wire pitch from any of these extrapolated wires, the method will not report error.

Todo:
When the ID is out of range, instead of throwing an exception, return an invalid wire ID with the wire number set to the non-existing wire which would be the nearest to pos.

Definition at line 485 of file PlaneGeo.cxx.

References ID(), Nwires(), and WireCoordinate().

Referenced by calo::TrackCalorimetryAlg::ExtractCalorimetry(), util::GeometryUtilities::Get2DPointProjection(), util::GeometryUtilities::Get2DPointProjectionCM(), opdet::GetHitGeometryInfo(), nnet::TrainingDataAlg::getProjection(), GetWireDirection(), apa::APAGeometryAlg::LineSegChanIntersect(), geo::WireReadoutGeom::NearestChannel(), NearestWire(), apa::APAGeometryAlg::NearestWireIDOnChan(), trk::TrackContainmentAlg::ProcessTracks(), and shower::EMShowerAlg::Project3DPointOntoPlane_().

486  {
487  // 1) compute the wire coordinate of the point
488  // 2) get the closest wire number
489  // 3) check if the wire does exist
490  // 4) build and return the wire ID
491 
492  // this line merges parts (1) and (2); add 0.5 to have the correct rounding:
493  int nearestWireNo = int(0.5 + WireCoordinate(pos));
494 
495  // if we are outside of the wireplane range, throw an exception
496  if ((nearestWireNo < 0) || ((unsigned int)nearestWireNo >= Nwires())) {
497 
498  auto wireNo = nearestWireNo; // save for the output
499 
500  if (nearestWireNo < 0)
501  wireNo = 0;
502  else
503  wireNo = Nwires() - 1;
504 
505  throw InvalidWireError("Geometry", ID(), nearestWireNo, wireNo)
506  << "Can't find nearest wire for position " << pos << " in plane " << std::string(ID())
507  << " approx wire number # " << wireNo << " (capped from " << nearestWireNo << ")\n";
508  } // if invalid
509 
510  return {ID(), (WireID::WireID_t)nearestWireNo};
511  }
double WireCoordinate(Point_t const &point) const
Returns the coordinate of the point on the plane, in wire units.
Definition: PlaneGeo.h:704
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
Exception thrown on invalid wire number.
Definition: Exceptions.h:37
unsigned int WireID_t
Type for the ID number.
Definition: geo_types.h:422
PlaneID const & ID() const
Returns the identifier of this plane.
Definition: PlaneGeo.h:173
unsigned int geo::PlaneGeo::NElements ( ) const
inline

Number of wires in this plane.

Definition at line 232 of file PlaneGeo.h.

References Nwires().

Referenced by geo::WireReadoutGeom::Nwires().

232 { return Nwires(); }
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
unsigned int geo::PlaneGeo::Nwires ( ) const
inline

Number of wires in this plane.

Definition at line 231 of file PlaneGeo.h.

Referenced by ClosestWireID(), Depth(), geo::WireReadoutDumper::dumpTPCplane(), GetNormalAxis(), HasWire(), LastWire(), MiddleWire(), NearestWireID(), NElements(), PrintPlaneInfo(), UpdateIncreasingWireDir(), and UpdateWirePitch().

231 { return fWire.size(); }
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
Orient_t geo::PlaneGeo::Orientation ( ) const
inline

What is the orientation of the plane.

Definition at line 158 of file PlaneGeo.h.

References fOrientation, and ThetaZ().

Referenced by PrintPlaneInfo().

158 { return fOrientation; }
Orient_t fOrientation
Is the plane vertical or horizontal?
Definition: PlaneGeo.h:1208
std::string geo::PlaneGeo::OrientationName ( Orient_t  orientation)
static

Returns the name of the specified orientation.

Definition at line 599 of file PlaneGeo.cxx.

References geo::kHorizontal, and geo::kVertical.

Referenced by PrintPlaneInfo(), and SetView().

600  {
601  switch (orientation) {
602  case kHorizontal: return "horizontal"; break;
603  case kVertical: return "vertical"; break;
604  default: return "unexpected"; break;
605  }
606  }
Planes that are in the horizontal plane.
Definition: geo_types.h:142
Planes that are in the vertical plane (e.g. ArgoNeuT).
Definition: geo_types.h:143
double geo::PlaneGeo::PhiZ ( ) const
inline

Angle from positive z axis of the wire coordinate axis, in radians.

Definition at line 164 of file PlaneGeo.h.

References fCosPhiZ, and fSinPhiZ.

Referenced by PrintPlaneInfo(), and geo::WireReadoutGeom::ThirdPlane_dTdW().

164 { return std::atan2(fSinPhiZ, fCosPhiZ); }
double fSinPhiZ
Sine of .
Definition: PlaneGeo.h:1211
double fCosPhiZ
Cosine of .
Definition: PlaneGeo.h:1212
double geo::PlaneGeo::PlaneCoordinate ( Point_t const &  point) const
inline

Returns the coordinate of the point on the plane.

Parameters
pointworld coordinate of the point to get the coordinate of [cm]
Returns
the coordinate of the point [cm]
See also
PlaneCoordinateFrom(TVector3 const&, geo::Wire const&)

The method returns the coordinate of the point in the direction measured by the wires on this plane starting on the first wire, in world units (that is, centimeters). A point on the first wire will have coordinate 0.0, one on the next wire will have coordinate equal to a single wire pitch, etc.

The point does not need to be on the plane, and the projection of the point to the plane is considered.

Definition at line 684 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::PointSecondaryComponent().

Referenced by WireCoordinate().

685  {
686  return fDecompWire.PointSecondaryComponent(point);
687  }
auto PointSecondaryComponent(Point_t const &point) const
Returns the secondary component of a point.
Definition: Decomposer.h:470
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
double geo::PlaneGeo::PlaneCoordinateFrom ( Point_t const &  point,
WireGeo const &  refWire 
) const
inline

Returns the coordinate of point on the plane respect to a wire.

Parameters
pointworld coordinate of the point to get the coordinate of [cm]
refWirereference wire
Returns
the coordinate of the point [cm]
See also
WireCoordinate()

The method returns the coordinate of the point in the direction measured by the wires on this plane starting from the specified reference wire, in world units (that is, centimeters).

The point does not need to be on the plane, and the projection of the point to the plane is considered. The reference wire, instead, must belong to this plane. This assumption is not checked, and if violated the results are undefined (in the current implementation, they are just wrong).

Definition at line 663 of file PlaneGeo.h.

References fDecompWire, geo::WireGeo::GetCenter(), and geo::Decomposer< Vector, Point, ProjVector >::VectorSecondaryComponent().

664  {
665  return fDecompWire.VectorSecondaryComponent(point - refWire.GetCenter());
666  }
auto VectorSecondaryComponent(Vector_t const &v) const
Returns the secondary component of a vector.
Definition: Decomposer.h:525
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
std::string geo::PlaneGeo::PlaneInfo ( std::string  indent = "",
unsigned int  verbosity = 1 
) const

Returns a string with plane information.

See also
PrintPlaneInfo()

The information is provided by PrintPlaneInfo(), and the arguments have the same meaning.

Definition at line 422 of file PlaneGeo.cxx.

References PrintPlaneInfo().

Referenced by ActiveArea().

424  {
425  std::ostringstream sstr;
426  PrintPlaneInfo(sstr, indent, verbosity);
427  return sstr.str();
428  }
std::string indent(std::size_t const i)
void PrintPlaneInfo(Stream &&out, std::string indent="", unsigned int verbosity=1) const
Prints information about this plane.
Definition: PlaneGeo.h:1258
WidthDepthProjection_t geo::PlaneGeo::PointWidthDepthProjection ( Point_t const &  point) const
inline

Returns the projection of the specified point on the plane.

Parameters
pointthe 3D point to be projected, in world coordinates
Returns
a 2D vector representing the projection of point on the plane

The returned vector is a 2D vector expressing the projection of the point (from world coordinates) on the wire plane. The vector is expressed as $ ( w, d ) $, components following the width direction (WidthDir()) and the depth direction (DepthDir()) respectively. The origin point is the center of the plane.

Definition at line 897 of file PlaneGeo.h.

References fDecompFrame, and geo::Decomposer< Vector, Point, ProjVector >::ProjectPointOnPlane().

Referenced by isProjectionOnPlane(), MovePointOverPlane(), and larg4::LArVoxelReadout::RecoverOffPlaneDeposit().

898  {
899  return fDecompFrame.ProjectPointOnPlane(point);
900  }
Projection_t ProjectPointOnPlane(Point_t const &point) const
Returns the projection of the specified point on the plane.
Definition: Decomposer.h:492
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
template<typename Stream >
void geo::PlaneGeo::PrintPlaneInfo ( Stream &&  out,
std::string  indent = "",
unsigned int  verbosity = 1 
) const

Prints information about this plane.

Template Parameters
Streamtype of output stream to use
Parameters
outstream to send the information to
indentprepend each line with this string
verbosityamount of information printed

Information on single wires is not printed. Note that the first line out the output is not indented.

Verbosity levels

  • 0: only plane ID
  • 1 _(default)_: also center and wire angle
  • 2: also information about wires
  • 3: also information about normal and increasing coordinate direction
  • 4: also information about wire direction, width and depth
  • 5: also coverage
  • 6: also bounding box

Definition at line 1258 of file PlaneGeo.h.

References ActiveArea(), BoundingBox(), Depth(), lar::util::simple_geo::Rectangle< Data >::depth, DepthDir(), fDecompFrame, fDecompWire, GetCenter(), GetIncreasingWireDirection(), GetNormalDirection(), GetWireDirection(), ID(), lar::util::simple_geo::Range< Data >::lower, geo::Decomposer< Vector, Point, ProjVector >::NormalDir(), Nwires(), Orientation(), OrientationName(), PhiZ(), ThetaZ(), lar::util::simple_geo::Range< Data >::upper, View(), ViewName(), Width(), lar::util::simple_geo::Rectangle< Data >::width, WidthDir(), WireIDincreasesWithZ(), and WirePitch().

Referenced by ActiveArea(), geo::WireReadoutDumper::dumpTPCplane(), and PlaneInfo().

1262 {
1263 
1264  //----------------------------------------------------------------------------
1265  out << "plane " << std::string(ID());
1266 
1267  if (verbosity-- <= 0) return; // 0
1268 
1269  //----------------------------------------------------------------------------
1270  out << " at " << GetCenter() << " cm"
1271  << ", theta: " << ThetaZ() << " rad";
1272 
1273  if (verbosity-- <= 0) return; // 1
1274 
1275  //----------------------------------------------------------------------------
1276  unsigned int const nWires = Nwires();
1277 
1278  out << "\n"
1279  << indent << "normal to wire: " << PhiZ() << " rad"
1280  << ", with orientation " << OrientationName(Orientation()) << ", has " << nWires
1281  << " wires measuring " << ViewName(View()) << " with a wire pitch of " << WirePitch()
1282  << " cm";
1283 
1284  if (verbosity-- <= 0) return; // 2
1285 
1286  //----------------------------------------------------------------------------
1287  auto const& normal = GetNormalDirection();
1288  auto const& incrZdir = GetIncreasingWireDirection();
1289  auto const& wireNormalDir = fDecompWire.NormalDir();
1290  out << "\n"
1291  << indent << "normal to plane: " << normal
1292  << ", direction of increasing wire number: " << incrZdir
1293  << " [wire frame normal: " << wireNormalDir << "]"
1294  << " (" << (WireIDincreasesWithZ() ? "increases" : "decreases") << " with z)";
1295 
1296  if (verbosity-- <= 0) return; // 3
1297 
1298  //----------------------------------------------------------------------------
1299 
1300  auto const& wireDir = GetWireDirection();
1301  auto const& widthDir = WidthDir();
1302  auto const& depthDir = DepthDir();
1303  auto const& frameNormalDir = fDecompFrame.NormalDir();
1304 
1305  out << "\n"
1306  << indent << "wire direction: " << wireDir << "; width " << Width()
1307  << " cm in direction: " << widthDir << ", depth " << Depth()
1308  << " cm in direction: " << depthDir << " [normal: " << frameNormalDir << "]";
1309 
1310  if (verbosity-- <= 0) return; // 4
1311 
1312  //----------------------------------------------------------------------------
1313  // get the area spanned by the wires
1314  out << "\n"
1315  << indent << "wires cover width " << ActiveArea().width.lower << " to "
1316  << ActiveArea().width.upper << ", depth " << ActiveArea().depth.lower << " to "
1317  << ActiveArea().depth.upper << " cm";
1318  if (verbosity-- <= 0) return; // 5
1319 
1320  //----------------------------------------------------------------------------
1321  // print also the containing box
1322  auto const box = BoundingBox();
1323  out << "\n" << indent << "bounding box: " << box.Min() << " -- " << box.Max();
1324 }
BoxBoundedGeo BoundingBox() const
Definition: PlaneGeo.cxx:370
static std::string ViewName(View_t view)
Returns the name of the specified view.
Definition: PlaneGeo.cxx:584
Vector_t const & DepthDir() const
Return the direction of plane depth.
Definition: PlaneGeo.h:201
Point_t const & GetCenter() const
Returns the centre of the wire plane in world coordinates [cm].
Definition: PlaneGeo.h:366
Vector_t const & NormalDir() const
Returns the plane normal axis direction.
Definition: Decomposer.h:456
Rect const & ActiveArea() const
Returns an area covered by the wires in the plane.
Definition: PlaneGeo.h:597
double ThetaZ() const
Angle of the wires from positive z axis; .
Definition: PlaneGeo.cxx:549
View_t View() const
Which coordinate does this plane measure.
Definition: PlaneGeo.h:155
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
double PhiZ() const
Angle from positive z axis of the wire coordinate axis, in radians.
Definition: PlaneGeo.h:164
Vector_t const & GetWireDirection() const
Returns the direction of the wires.
Definition: PlaneGeo.h:390
double Depth() const
Return the depth of the plane.
Definition: PlaneGeo.h:218
std::string indent(std::size_t const i)
double Width() const
Return the width of the plane.
Definition: PlaneGeo.h:210
Range_t width
Range along width direction.
Definition: SimpleGeo.h:428
static std::string OrientationName(Orient_t orientation)
Returns the name of the specified orientation.
Definition: PlaneGeo.cxx:599
Orient_t Orientation() const
What is the orientation of the plane.
Definition: PlaneGeo.h:158
Range_t depth
Range along depth direction.
Definition: SimpleGeo.h:429
Vector_t const & WidthDir() const
Return the direction of plane width.
Definition: PlaneGeo.h:189
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
bool WireIDincreasesWithZ() const
Returns whether the higher z wires have higher wire ID.
Definition: PlaneGeo.cxx:416
Data_t upper
Ending coordinate.
Definition: SimpleGeo.h:358
Vector_t const & GetIncreasingWireDirection() const
Returns the direction of increasing wires.
Definition: PlaneGeo.h:350
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Data_t lower
Starting coordinate.
Definition: SimpleGeo.h:357
PlaneID const & ID() const
Returns the identifier of this plane.
Definition: PlaneGeo.h:173
double WirePitch() const
Return the wire pitch (in centimeters). It is assumed constant.
Definition: PlaneGeo.h:312
WireCoordProjection_t geo::PlaneGeo::Projection ( Point_t const &  point) const
inline

Returns the projection of the specified point on the plane.

Parameters
pointthe 3D point to be projected, in world coordinates
Returns
a 2D vector representing the projection of point on the plane

The returned vector is a 2D vector expressing the projection of the point (from world coordinates) on the wire plane. The vector is expressed as $ ( \ell, w ) $. The component $ \ell $ is measured on the direction of the first wire (see WireGeo::Direction()), using its center (see WireGeo::GetCenter()) as reference point. The component $ w $ is defined on the wire coordinate direction (see GetIncreasingWireDirection()), relative to the first wire, as it is returned by PlaneCoordinate().

The reference point is also returned by ProjectionReferencePoint().

Definition at line 755 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::ProjectPointOnPlane().

Referenced by InterWireProjectedDistance(), and lar::util::TrackPitchInView().

756  {
757  return fDecompWire.ProjectPointOnPlane(point);
758  }
Projection_t ProjectPointOnPlane(Point_t const &point) const
Returns the projection of the specified point on the plane.
Definition: Decomposer.h:492
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
WireCoordProjection_t geo::PlaneGeo::Projection ( Vector_t const &  v) const
inline

Returns the projection of the specified vector on the plane.

Parameters
vthe 3D vector to be projected, in world units
Returns
a 2D vector representing the projection of v on the plane

The returned vector is a 2D vector expressing the projection of the vector (from world units) on the wire plane. The vector is expressed as $ ( \ell, w ) $. The component $ \ell $ is measured on the direction of the first wire (see WireGeo::Direction()). The component $ w $ is defined on the wire coordinate direction (see GetIncreasingWireDirection()).

Definition at line 773 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::ProjectVectorOnPlane().

774  {
776  }
Projection_t ProjectVectorOnPlane(Vector_t const &v) const
Returns the projection of the specified vector on the plane.
Definition: Decomposer.h:544
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Point_t geo::PlaneGeo::ProjectionReferencePoint ( ) const
inline

Returns the reference point used by PointProjection().

The returned point is such that its decomposition results in a null projection and a 0 distance from the plane.

Definition at line 736 of file PlaneGeo.h.

References fDecompWire, and geo::Decomposer< Vector, Point, ProjVector >::ReferencePoint().

736 { return fDecompWire.ReferencePoint(); }
Point_t ReferencePoint() const
Returns the reference point for the plane coordinate, as a 3D point.
Definition: Decomposer.h:444
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
void geo::PlaneGeo::SetView ( View_t  view)
inline

Set the signal view (for TPCGeo).

Definition at line 1128 of file PlaneGeo.h.

References fView, OrientationName(), SortWires(), UpdateAfterSorting(), and ViewName().

Referenced by UpdateView().

1128 { fView = view; }
View_t fView
Does this plane measure U, V, or W?
Definition: PlaneGeo.h:1207
bool geo::PlaneGeo::shouldFlipWire ( WireGeo const &  wire) const
private

Whether the specified wire should have start and end swapped.

Definition at line 953 of file PlaneGeo.cxx.

References geo::WireGeo::Direction(), GetIncreasingWireDirection(), and GetNormalDirection().

Referenced by UpdateAfterSorting(), and Volume().

954  {
955  // The correct orientation is so that:
956  //
957  // (direction) x (wire coordinate direction) . (plane normal)
958  //
959  // is positive; it it's negative, then we should flip the wire.
960  //
961  // Note that the increasing wire direction comes from the wire frame, while the normal
962  // direction is computed independently by geometry. The resulting normal in the wire
963  // frame is expected to be the same as the plane normal from GetNormalDirection(); if
964  // this is not the case, flipping the wire direction should restore it.
965 
966  return wire.Direction().Cross(GetIncreasingWireDirection()).Dot(GetNormalDirection()) <
967  +0.5; // should be in fact exactly +1
968  }
Vector_t const & GetIncreasingWireDirection() const
Returns the direction of increasing wires.
Definition: PlaneGeo.h:350
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
double geo::PlaneGeo::SinPhiZ ( ) const
inline

Sine of PhiZ()

Definition at line 167 of file PlaneGeo.h.

References fSinPhiZ.

167 { return fSinPhiZ; }
double fSinPhiZ
Sine of .
Definition: PlaneGeo.h:1211
void geo::PlaneGeo::SortWires ( Compare< WireGeo cmp)

Apply sorting to WireGeo objects.

Definition at line 410 of file PlaneGeo.cxx.

References fWire.

Referenced by SetView().

411  {
412  std::sort(fWire.begin(), fWire.end(), cmp);
413  }
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
double geo::PlaneGeo::ThetaZ ( ) const

Angle of the wires from positive z axis; $ \theta_{z} \in [ 0, \pi ]$.

Definition at line 549 of file PlaneGeo.cxx.

References FirstWire(), and geo::WireGeo::ThetaZ().

Referenced by tca::dEdx(), Orientation(), and PrintPlaneInfo().

550  {
551  return FirstWire().ThetaZ();
552  }
double ThetaZ() const
Returns angle of wire with respect to z axis in the Y-Z plane in radians.
Definition: WireGeo.h:246
WireGeo const & FirstWire() const
Return the first wire in the plane.
Definition: PlaneGeo.h:298
LocalPoint_t geo::PlaneGeo::toLocalCoords ( Point_t const &  world) const
inline

Transform point from world frame to local plane frame.

Definition at line 1117 of file PlaneGeo.h.

References fTrans, and geo::LocalTransformationGeo< StoredMatrix, LocalPoint, LocalVector >::toLocalCoords().

1117 { return fTrans.toLocalCoords(world); }
LocalPoint_t toLocalCoords(GlobalPoint_t const &world) const
Transforms a point from world frame to local frame.
LocalTransformation_t fTrans
Plane to world transform.
Definition: PlaneGeo.h:1206
LocalVector_t geo::PlaneGeo::toLocalCoords ( Vector_t const &  world) const
inline

Transform direction vector from world to local.

Definition at line 1120 of file PlaneGeo.h.

References fTrans, and geo::LocalTransformationGeo< StoredMatrix, LocalPoint, LocalVector >::toLocalCoords().

1120 { return fTrans.toLocalCoords(world); }
LocalPoint_t toLocalCoords(GlobalPoint_t const &world) const
Transforms a point from world frame to local frame.
LocalTransformation_t fTrans
Plane to world transform.
Definition: PlaneGeo.h:1206
Point_t geo::PlaneGeo::toWorldCoords ( LocalPoint_t const &  local) const
inline

Transform point from local plane frame to world frame.

Definition at line 1111 of file PlaneGeo.h.

Referenced by BoundingBox(), ComposePoint(), DetectGeometryDirections(), util::GeometryUtilities::Get2DPointProjection(), GetBoxCenter(), and util::GeometryUtilities::GetProjectedPoint().

1111 { return fTrans.toWorldCoords(local); }
LocalTransformation_t fTrans
Plane to world transform.
Definition: PlaneGeo.h:1206
GlobalPoint_t toWorldCoords(LocalPoint_t const &local) const
Transforms a point from local frame to world frame.
Vector_t geo::PlaneGeo::toWorldCoords ( LocalVector_t const &  local) const
inline

Transform direction vector from local to world.

Definition at line 1114 of file PlaneGeo.h.

References fTrans, and geo::LocalTransformationGeo< StoredMatrix, LocalPoint, LocalVector >::toWorldCoords().

1114 { return fTrans.toWorldCoords(local); }
LocalTransformation_t fTrans
Plane to world transform.
Definition: PlaneGeo.h:1206
GlobalPoint_t toWorldCoords(LocalPoint_t const &local) const
Transforms a point from local frame to world frame.
TGeoVolume const* geo::PlaneGeo::TPCVolume ( ) const
inline

Definition at line 149 of file PlaneGeo.h.

References fNode.

149 { return fNode->GetMotherVolume(); }
TGeoNode const * fNode
Node within full geometry.
Definition: PlaneGeo.h:1205
void geo::PlaneGeo::UpdateActiveArea ( )
private

Updates the internally used active area.

Definition at line 916 of file PlaneGeo.cxx.

References fActiveArea.

Referenced by UpdateAfterSorting(), and Volume().

917  {
918  // The active area is defined in the width/depth space which include approximatively
919  // all wires.
920  //
921  // See `ActiveAreaCalculator` for details of the algorithm.
922 
923  // we scratch 1 um from each side to avoid rounding errors later
924  fActiveArea = ActiveAreaCalculator(*this, 0.0001);
925  }
Rect fActiveArea
Area covered by wires in frame base.
Definition: PlaneGeo.h:1225
void geo::PlaneGeo::UpdateAfterSorting ( PlaneID  planeid,
BoxBoundedGeo const &  TPCbox 
)

Performs all needed updates after the TPC has sorted the planes.

Definition at line 555 of file PlaneGeo.cxx.

References fID, fWire, shouldFlipWire(), UpdateActiveArea(), UpdateDecompWireOrigin(), UpdateIncreasingWireDir(), UpdateOrientation(), UpdatePhiZ(), UpdatePlaneNormal(), UpdateView(), UpdateWidthDepthDir(), UpdateWireDir(), UpdateWirePitch(), and UpdateWirePlaneCenter().

Referenced by SetView().

556  {
557  // the order here matters
558 
559  // reset our ID
560  fID = planeid;
561 
562  UpdatePlaneNormal(TPCbox);
565 
566  // update wires
567  WireID::WireID_t wireNo = 0;
568  for (auto& wire : fWire) {
569  wire.UpdateAfterSorting(WireID(fID, wireNo), shouldFlipWire(wire));
570  ++wireNo;
571  } // for wires
572 
574  UpdateWireDir();
577  UpdateWirePitch();
579  UpdatePhiZ();
580  UpdateView();
581  }
void UpdateIncreasingWireDir()
Updates the cached direction to increasing wires.
Definition: PlaneGeo.cxx:856
void UpdateWirePitch()
Updates the stored wire pitch.
Definition: PlaneGeo.cxx:721
void UpdateWidthDepthDir()
Updates the cached depth and width direction.
Definition: PlaneGeo.cxx:842
void UpdateOrientation()
Updates plane orientation.
Definition: PlaneGeo.cxx:694
PlaneID fID
ID of this plane.
Definition: PlaneGeo.h:1229
void UpdatePlaneNormal(BoxBoundedGeo const &TPCbox)
Updates the cached normal to plane versor; needs the TPC box coordinates.
Definition: PlaneGeo.cxx:826
IDparameter< geo::WireID > WireID
Member type of validated geo::WireID parameter.
void UpdatePhiZ()
Updates the stored .
Definition: PlaneGeo.cxx:733
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
void UpdateView()
Updates the stored view.
Definition: PlaneGeo.cxx:740
unsigned int WireID_t
Type for the ID number.
Definition: geo_types.h:422
void UpdateWirePlaneCenter()
Updates the stored wire plane center.
Definition: PlaneGeo.cxx:928
bool shouldFlipWire(WireGeo const &wire) const
Whether the specified wire should have start and end swapped.
Definition: PlaneGeo.cxx:953
void UpdateDecompWireOrigin()
Updates the position of the wire coordinate decomposition.
Definition: PlaneGeo.cxx:909
void UpdateActiveArea()
Updates the internally used active area.
Definition: PlaneGeo.cxx:916
void UpdateWireDir()
Updates the cached direction to wire.
Definition: PlaneGeo.cxx:880
void geo::PlaneGeo::UpdateDecompWireOrigin ( )
private

Updates the position of the wire coordinate decomposition.

Definition at line 909 of file PlaneGeo.cxx.

References fDecompWire, FirstWire(), GetCenter(), geo::Decomposer< Vector, Point, ProjVector >::SetOrigin(), and geo::vect::toPoint().

Referenced by UpdateAfterSorting(), and Volume().

910  {
911  // update the origin of the reference frame (the middle of the first wire)
913  }
Point_t const & GetCenter() const
Returns the centre of the wire plane in world coordinates [cm].
Definition: PlaneGeo.h:366
WireGeo const & FirstWire() const
Return the first wire in the plane.
Definition: PlaneGeo.h:298
Point_t toPoint(Point const &p)
Convert the specified point into a geo::Point_t.
void SetOrigin(Point_t const &point)
Change the 3D point of the reference frame origin.
Definition: Decomposer.h:430
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
void geo::PlaneGeo::UpdateIncreasingWireDir ( )
private

Updates the cached direction to increasing wires.

Definition at line 856 of file PlaneGeo.cxx.

References e, fDecompWire, geo::WireGeo::GetCenter(), GetNormalDirection(), Nwires(), geo::vect::rounded01(), geo::Decomposer< Vector, Point, ProjVector >::SetSecondaryDir(), and Wire().

Referenced by UpdateAfterSorting(), and Volume().

857  {
858  // Direction measured by the wires, pointing toward increasing wire number; requires:
859  // - the normal to the plane to be correct
860  // - wires to be sorted
861 
862  // 1) get the direction of the middle wire
863  auto refWireNo = Nwires() / 2;
864  if (refWireNo == Nwires() - 1) --refWireNo;
865  auto const& refWire = Wire(refWireNo);
866  auto const& WireDir = refWire.Direction(); // we only rely on the axis
867 
868  // 2) get the axis perpendicular to it on the wire plane (arbitrary direction)
869  auto wireCoordDir = GetNormalDirection().Cross(WireDir).Unit();
870 
871  // 3) where is the next wire?
872  auto toNextWire = Wire(refWireNo + 1).GetCenter() - refWire.GetCenter();
873 
874  // 4) if wireCoordDir is pointing away from the next wire, flip it
875  if (wireCoordDir.Dot(toNextWire) < 0) { wireCoordDir = -wireCoordDir; }
876  fDecompWire.SetSecondaryDir(vect::rounded01(wireCoordDir, 1e-4));
877  }
Point_t const & GetCenter() const
Returns the world coordinate of the center of the wire [cm].
Definition: WireGeo.h:219
void SetSecondaryDir(Vector_t const &dir)
Change the secondary direction of the projection base.
Definition: Decomposer.h:436
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
Vector rounded01(Vector const &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Float_t e
Definition: plot.C:35
void geo::PlaneGeo::UpdateOrientation ( )
private

Updates plane orientation.

Definition at line 694 of file PlaneGeo.cxx.

References util::abs(), e, fOrientation, fWire, GetNormalDirection(), geo::kHorizontal, and geo::kVertical.

Referenced by UpdateAfterSorting(), and Volume().

695  {
696  // this algorithm needs to know about the axis; the normal is expected to be already
697  // updated.
698 
699  // sanity check
700  if (fWire.size() < 2) {
701  // this likely means construction is not complete yet
702  throw cet::exception("NoWireInPlane")
703  << "PlaneGeo::UpdateOrientation(): only " << fWire.size() << " wires!\n";
704  } // if
705 
706  auto normal = GetNormalDirection();
707 
708  if (std::abs(std::abs(normal.X()) - 1.) < 1e-3)
710  else if (std::abs(std::abs(normal.Y()) - 1.) < 1e-3)
712  else {
713  // at this point, the only problem is the lack of a label for this orientation;
714  // probably introducing a geo::kOtherOrientation would suffice
715  throw cet::exception("Geometry")
716  << "Plane with unsupported orientation (normal: " << normal << ")\n";
717  }
718  }
constexpr auto abs(T v)
Returns the absolute value of the argument.
Planes that are in the horizontal plane.
Definition: geo_types.h:142
Planes that are in the vertical plane (e.g. ArgoNeuT).
Definition: geo_types.h:143
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
Float_t e
Definition: plot.C:35
Orient_t fOrientation
Is the plane vertical or horizontal?
Definition: PlaneGeo.h:1208
cet::coded_exception< error, detail::translate > exception
Definition: exception.h:33
void geo::PlaneGeo::UpdatePhiZ ( )
private

Updates the stored $ \phi_{z} $.

Definition at line 733 of file PlaneGeo.cxx.

References fCosPhiZ, fSinPhiZ, and GetIncreasingWireDirection().

Referenced by UpdateAfterSorting(), and Volume().

734  {
735  auto const& wire_coord_dir = GetIncreasingWireDirection();
736  fCosPhiZ = wire_coord_dir.Z();
737  fSinPhiZ = wire_coord_dir.Y();
738  }
double fSinPhiZ
Sine of .
Definition: PlaneGeo.h:1211
double fCosPhiZ
Cosine of .
Definition: PlaneGeo.h:1212
Vector_t const & GetIncreasingWireDirection() const
Returns the direction of increasing wires.
Definition: PlaneGeo.h:350
void geo::PlaneGeo::UpdatePlaneNormal ( BoxBoundedGeo const &  TPCbox)
private

Updates the cached normal to plane versor; needs the TPC box coordinates.

Definition at line 826 of file PlaneGeo.cxx.

References geo::BoxBoundedGeo::Center(), e, fNormal, GetBoxCenter(), GetNormalAxis(), and geo::vect::round01().

Referenced by UpdateAfterSorting(), and Volume().

827  {
828  // direction normal to the wire plane, points toward the center of TPC
829 
830  // start from the axis
832 
833  // now evaluate where we are pointing
834  auto const towardCenter = TPCbox.Center() - GetBoxCenter();
835 
836  // if they are pointing in opposite directions, flip the normal
837  if (fNormal.Dot(towardCenter) < 0) fNormal = -fNormal;
838  vect::round01(fNormal, 1e-3);
839  }
void round01(Vector &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
Vector_t GetNormalAxis() const
Returns a direction normal to the plane (pointing is not defined).
Definition: PlaneGeo.cxx:676
Vector_t fNormal
Definition: PlaneGeo.h:1214
Point_t GetBoxCenter() const
Returns the centre of the box representing the plane.
Definition: PlaneGeo.h:380
Float_t e
Definition: plot.C:35
void geo::PlaneGeo::UpdateView ( )
private

Updates the stored view.

This algorithm assigns views according to the angle the wire axis cuts with y axis ("thetaY"), but from the point of view of the center of the TPC. A special case is when the drift axis is on y axis.

In the normal case, the discrimination happens on the the arctangent of the point { (y,w), (y x n,w) }, where w is the wire direction, y is the coordinate axis and n the normal to the wire plane. This definition gives the same value regardless of the direction of w on its axis.

If thetaY is 0, wires are parallel to the y axis, the view is assigned as kX or kZ depending on whether the plane normal is closer to the z axis or the x axis, respectively (the normal describes a direction not measured by the wires).

If thetaY is a right angle, the wires are orthogonal to y axis and view kY view is assigned. If thetaY is smaller than 0, the view is called "U". If thetaY is larger than 0, the view is called "V".

The special case where the drift axis is on y axis is treated separately. In that case, the role of y axis is replaced by the z axis and the discriminating figure is equivalent to the usual ThetaZ().

If thetaZ is 0, the wires are measuring x and kX view is chosen. If thetaZ is a right angle, the wires are measuring z and kZ view is chosen. If thetaZ is smaller than 0, the view is called "U". If thetaZ is larger than 0, the view is called "V".

Definition at line 740 of file PlaneGeo.cxx.

References util::abs(), geo::vect::dot(), e, GetNormalDirection(), GetWireDirection(), geo::kU, geo::kV, geo::kX, geo::kY, geo::kZ, geo::vect::mixedProduct(), SetView(), geo::Xaxis(), geo::Yaxis(), and geo::Zaxis().

Referenced by UpdateAfterSorting(), and Volume().

741  {
771  auto const& normalDir = GetNormalDirection();
772  auto const& wireDir = GetWireDirection();
773 
774  // normal direction has been rounded, so exact comparison can work
775  if (std::abs(normalDir.Y()) != 1.0) {
776  // normal case: drift direction is not along y (vertical)
777 
778  // yw is pretty much GetWireDirection().Y()... thetaY is related to atan2(ynw, yw)
779  double const yw = vect::dot(wireDir, Yaxis());
780  double const ynw = vect::mixedProduct(Yaxis(), normalDir, wireDir);
781 
782  if (std::abs(yw) < 1.0e-4) { // wires orthogonal to y axis
783  double const closeToX = std::abs(vect::dot(normalDir, Xaxis()));
784  double const closeToZ = std::abs(vect::dot(normalDir, Zaxis()));
785  SetView((closeToZ > closeToX) ? kX : kY);
786  }
787  else if (std::abs(ynw) < 1.0e-4) { // wires parallel to y axis
788  SetView(kZ);
789  }
790  else if ((ynw * yw) < 0)
791  SetView(kU); // different sign => thetaY > 0
792  else if ((ynw * yw) > 0)
793  SetView(kV); // same sign => thetaY < 0
794  else
795  assert(false); // logic error?!
796  }
797  else { // if drift is vertical
798  // special case: drift direction is along y (vertical)
799 
800  // zw is pretty much GetWireDirection().Z()...
801  double const zw = vect::dot(wireDir, Zaxis());
802  // while GetNormalDirection() axis is on y, its direction is not fixed:
803  double const znw = vect::mixedProduct(Zaxis(), normalDir, wireDir);
804 
805  // thetaZ is std::atan(znw/zw)
806 
807  if (std::abs(zw) < 1.0e-4) { // orthogonal to z, orthogonal to y...
808  // this is equivalent to thetaZ = +/- pi/2
809  SetView(kZ);
810  }
811  else if (std::abs(znw) < 1.0e-4) { // parallel to z, orthogonal to y...
812  // this is equivalent to thetaZ = 0
813  SetView(kX);
814  }
815  else if ((znw * zw) < 0)
816  SetView(kU); // different sign => thetaZ > 0
817  else if ((znw * zw) > 0)
818  SetView(kV); // same sign => thetaZ < 0
819  else
820  assert(false); // logic error?!
821 
822  } // if drift direction... else
823  }
Planes which measure V.
Definition: geo_types.h:132
auto mixedProduct(Vector const &a, Vector const &b, Vector const &c)
Planes which measure X direction.
Definition: geo_types.h:136
constexpr Vector Yaxis()
Returns a y axis vector of the specified type.
Definition: geo_vectors.h:215
constexpr auto abs(T v)
Returns the absolute value of the argument.
Planes which measure Z direction.
Definition: geo_types.h:134
Planes which measure Y direction.
Definition: geo_types.h:135
Planes which measure U.
Definition: geo_types.h:131
Vector_t const & GetWireDirection() const
Returns the direction of the wires.
Definition: PlaneGeo.h:390
constexpr Vector Xaxis()
Returns a x axis vector of the specified type.
Definition: geo_vectors.h:208
constexpr auto dot(Vector const &a, OtherVector const &b)
Return cross product of two vectors.
void SetView(View_t view)
Set the signal view (for TPCGeo).
Definition: PlaneGeo.h:1128
constexpr Vector Zaxis()
Returns a z axis vector of the specified type.
Definition: geo_vectors.h:222
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
Float_t e
Definition: plot.C:35
void geo::PlaneGeo::UpdateWidthDepthDir ( )
private

Updates the cached depth and width direction.

Definition at line 842 of file PlaneGeo.cxx.

References DepthDir(), e, fDecompFrame, GetNormalDirection(), geo::vect::rounded01(), geo::Decomposer< Vector, Point, ProjVector >::SecondaryDir(), geo::Decomposer< Vector, Point, ProjVector >::SetSecondaryDir(), and WidthDir().

Referenced by UpdateAfterSorting(), and Volume().

843  {
844  // fix the positiveness of the width/depth/normal frame
845 
846  // The basis is already set and orthonormal, with only the width and depth directions
847  // arbitrary. We choose the direction of the secondary axis ("depth") so that the
848  // frame normal is oriented in the general direction of the plane normal (the latter
849  // is computed independently).
850  if (WidthDir().Cross(DepthDir()).Dot(GetNormalDirection()) < 0.0) {
852  }
853  }
void SetSecondaryDir(Vector_t const &dir)
Change the secondary direction of the projection base.
Definition: Decomposer.h:436
Vector_t const & DepthDir() const
Return the direction of plane depth.
Definition: PlaneGeo.h:201
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Vector rounded01(Vector const &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
Vector_t const & SecondaryDir() const
Returns the plane secondary axis direction.
Definition: Decomposer.h:453
Vector_t const & WidthDir() const
Return the direction of plane width.
Definition: PlaneGeo.h:189
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
Float_t e
Definition: plot.C:35
void geo::PlaneGeo::UpdateWireDir ( )
private

Updates the cached direction to wire.

Definition at line 880 of file PlaneGeo.cxx.

References e, fDecompWire, FirstWire(), GetNormalDirection(), lar::util::makeVector3DComparison(), geo::Decomposer< Vector, Point, ProjVector >::NormalDir(), geo::vect::rounded01(), and geo::Decomposer< Vector, Point, ProjVector >::SetMainDir().

Referenced by UpdateAfterSorting(), and Volume().

881  {
883 
884  // check that the resulting normal matches the plane one
885  assert(
887  }
Vector_t const & NormalDir() const
Returns the plane normal axis direction.
Definition: Decomposer.h:456
auto makeVector3DComparison(RealType threshold)
Creates a Vector3DComparison from a RealComparisons object.
WireGeo const & FirstWire() const
Return the first wire in the plane.
Definition: PlaneGeo.h:298
Vector rounded01(Vector const &v, Scalar tol)
Returns a vector with all components rounded if close to 0, -1 or +1.
Vector_t const & GetNormalDirection() const
Returns the direction normal to the plane.
Definition: PlaneGeo.h:339
Direction
Definition: types.h:12
WireDecomposer_t fDecompWire
Definition: PlaneGeo.h:1218
Float_t e
Definition: plot.C:35
void SetMainDir(Vector_t const &dir)
Change the main direction of the projection base.
Definition: Decomposer.h:433
void geo::PlaneGeo::UpdateWirePitch ( )
private

Updates the stored wire pitch.

Definition at line 721 of file PlaneGeo.cxx.

References fWirePitch, Nwires(), Wire(), and geo::WireGeo::WirePitch().

Referenced by UpdateAfterSorting(), and Volume().

722  {
723  // pick long wires around the center of the detector, so that their coordinates are
724  // defined with better precision
725  assert(Nwires() > 1);
726 
727  auto const iWire = Nwires() / 2;
728 
729  fWirePitch = WireGeo::WirePitch(Wire(iWire - 1), Wire(iWire));
730  }
double fWirePitch
Pitch of wires in this plane.
Definition: PlaneGeo.h:1210
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
unsigned int Nwires() const
Number of wires in this plane.
Definition: PlaneGeo.h:231
static double WirePitch(WireGeo const &w1, WireGeo const &w2)
Returns the pitch (distance on y/z plane) between two wires, in cm.
Definition: WireGeo.h:447
void geo::PlaneGeo::UpdateWirePitchSlow ( )
private

Updates the stored wire pitch with a slower, more robust algorithm.

Definition at line 890 of file PlaneGeo.cxx.

References e, fWire, fWirePitch, and geo::WireGeo::WirePitch().

Referenced by PlaneGeo(), and Volume().

891  {
892  if (fWire.empty()) { return; }
893 
894  // Compare one wire (the first one, for convenience) with all other wires; the wire
895  // pitch is the smallest distance we find.
896  //
897  // This algorithm assumes wire pitch is constant, but it does not assume wire ordering
898  auto firstWire = fWire.cbegin(), wire = firstWire, wend = fWire.cend();
899  fWirePitch = WireGeo::WirePitch(*firstWire, *(++wire));
900 
901  while (++wire != wend) {
902  auto wirePitch = WireGeo::WirePitch(*firstWire, *wire);
903  if (wirePitch < 1e-4) continue; // it's 0!
904  if (wirePitch < fWirePitch) fWirePitch = wirePitch;
905  }
906  }
double fWirePitch
Pitch of wires in this plane.
Definition: PlaneGeo.h:1210
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
static double WirePitch(WireGeo const &w1, WireGeo const &w2)
Returns the pitch (distance on y/z plane) between two wires, in cm.
Definition: WireGeo.h:447
Float_t e
Definition: plot.C:35
void geo::PlaneGeo::UpdateWirePlaneCenter ( )
private

Updates the stored wire plane center.

Definition at line 928 of file PlaneGeo.cxx.

References DistanceFromPlane(), DriftPoint(), e, fCenter, fDecompFrame, GetBoxCenter(), geo::vect::round0(), and geo::Decomposer< Vector, Point, ProjVector >::SetOrigin().

Referenced by UpdateAfterSorting(), and Volume().

929  {
930  // The center of the wire plane is defined as the center of the plane box, translated
931  // to the plane the wires lie on. This assumes that the thickness direction of the
932  // box is aligned with the drift direction, so that the translated point is still in
933  // the middle of width and depth dimensions. It is possible to remove that assumption
934  // by translating the center of the box along the thickness direction enough to bring
935  // it to the wire plane. The math is just a bit less straightforward, so we don't
936  // bother yet.
937  //
938  // Requirements:
939  // * the wire decomposition frame must be set up (at least its origin and normal
940  // direction)
941 
942  fCenter = GetBoxCenter();
943 
945 
946  vect::round0(fCenter, 1e-7); // round dimensions less than 1 nm to 0
947 
948  fDecompFrame.SetOrigin(fCenter); // equivalent to GetCenter() now
949 
950  } // PlaneGeo::UpdateWirePlaneCenter()
Point_t fCenter
Center of the plane, lying on the wire plane.
Definition: PlaneGeo.h:1227
double DistanceFromPlane(Point_t const &point) const
Returns the distance of the specified point from the wire plane.
Definition: PlaneGeo.h:484
void round0(Vector &v, Scalar tol)
Returns a vector with all components rounded if close to 0.
void DriftPoint(Point_t &position, double distance) const
Shifts the position of an electron drifted by a distance.
Definition: PlaneGeo.h:503
Point_t GetBoxCenter() const
Returns the centre of the box representing the plane.
Definition: PlaneGeo.h:380
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
void SetOrigin(Point_t const &point)
Change the 3D point of the reference frame origin.
Definition: Decomposer.h:430
Float_t e
Definition: plot.C:35
WidthDepthProjection_t geo::PlaneGeo::VectorWidthDepthProjection ( Vector_t const &  v) const
inline

Returns the projection of the specified vector on the plane.

Parameters
vthe 3D vector to be projected, in world units
Returns
a 2D vector representing the projection of v on the plane

The returned vector is a 2D vector expressing the projection of the vector (from world units) on the wire plane. The vector is expressed as $ ( w, d ) $, components following the width direction (WidthDir()) and the depth direction (DepthDir()) respectively.

Definition at line 914 of file PlaneGeo.h.

References DeltaFromPlane(), fDecompFrame, isProjectionOnPlane(), proj, and geo::Decomposer< Vector, Point, ProjVector >::ProjectVectorOnPlane().

915  {
917  }
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Projection_t ProjectVectorOnPlane(Vector_t const &v) const
Returns the projection of the specified vector on the plane.
Definition: Decomposer.h:544
std::string geo::PlaneGeo::ViewName ( View_t  view)
static

Returns the name of the specified view.

Definition at line 584 of file PlaneGeo.cxx.

References geo::k3D, geo::kU, geo::kUnknown, geo::kV, geo::kX, geo::kY, geo::kZ, and util::to_string().

Referenced by nnet::WaveformDenoiseTest::analyze(), nnet::NoiseWaveformDump::analyze(), nnet::RawWaveformDump::analyze(), nnet::RawWaveformClnSigDump::analyze(), trkf::SeedFinderAlgorithm::GetCenterAndDirection(), PrintPlaneInfo(), SetView(), lar::util::TrackPitchInView(), and geo::WireReadoutGeom::WireAngleToVertical().

585  {
586  switch (view) {
587  case kU: return "U";
588  case kV: return "V";
589  case kZ: return "Z";
590  case kY: return "Y";
591  case kX: return "X";
592  case k3D: return "3D";
593  case kUnknown: return "?";
594  default: return "<UNSUPPORTED (" + std::to_string((int)view) + ")>";
595  }
596  }
Planes which measure V.
Definition: geo_types.h:132
Unknown view.
Definition: geo_types.h:138
Planes which measure X direction.
Definition: geo_types.h:136
Planes which measure Z direction.
Definition: geo_types.h:134
Planes which measure Y direction.
Definition: geo_types.h:135
3-dimensional objects, potentially hits, clusters, prongs, etc.
Definition: geo_types.h:137
Planes which measure U.
Definition: geo_types.h:131
decltype(auto) constexpr to_string(T &&obj)
ADL-aware version of std::to_string.
TGeoVolume const& geo::PlaneGeo::Volume ( ) const
inlineprivate
double geo::PlaneGeo::Width ( ) const
inline

Return the width of the plane.

See also
Depth(), WidthDir(), DepthDir()

The precise definition is arbitrary (see WidthDir()).

Definition at line 210 of file PlaneGeo.h.

References fFrameSize, and geo::PlaneGeo::RectSpecs::Width().

Referenced by PrintPlaneInfo().

210 { return fFrameSize.Width(); }
RectSpecs fFrameSize
Definition: PlaneGeo.h:1223
double Width() const
Definition: PlaneGeo.h:1201
Vector_t const& geo::PlaneGeo::WidthDir ( ) const
inline

Return the direction of plane width.

The precise definition of the sides is arbitrary, but they are defined to lie on the wire plane and so that WidthDir(), DepthDir() and GetNormalDirection() make a orthonormal base. That base (width, depth, normal) is guaranteed to be positive defined.

Definition at line 189 of file PlaneGeo.h.

References fDecompFrame, and geo::Decomposer< Vector, Point, ProjVector >::MainDir().

Referenced by MovePointOverPlane(), PrintPlaneInfo(), and UpdateWidthDepthDir().

189 { return fDecompFrame.MainDir(); }
WidthDepthDecomposer_t fDecompFrame
Definition: PlaneGeo.h:1222
Vector_t const & MainDir() const
Returns the plane main axis direction.
Definition: Decomposer.h:450
WireGeo const & geo::PlaneGeo::Wire ( unsigned int  iwire) const

Return the iwire'th wire in the plane.

Exceptions
cet::exception(category "WireOutOfRange") if no such wire
Note
In the past, no check was performed.

Definition at line 403 of file PlaneGeo.cxx.

References WirePtr().

Referenced by geo::WireReadoutDumper::dumpTPCplane(), FirstWire(), GetElement(), GetNormalAxis(), HasElement(), LastWire(), MiddleWire(), NearestWire(), UpdateIncreasingWireDir(), UpdateWirePitch(), and geo::WireReadoutGeom::Wire().

404  {
405  if (WireGeo const* pWire = WirePtr(iwire)) { return *pWire; }
406  throw cet::exception("WireOutOfRange") << "Request for non-existant wire " << iwire << "\n";
407  }
Geometry description of a TPC wireThe wire is a single straight segment on a wire plane...
Definition: WireGeo.h:112
auto WirePtr(unsigned int iwire) const
Returns the wire number iwire from this plane.
Definition: PlaneGeo.h:282
cet::coded_exception< error, detail::translate > exception
Definition: exception.h:33
WireGeo const& geo::PlaneGeo::Wire ( WireID const &  wireid) const
inline

Returns the wire in wireid from this plane.

Parameters
wireidfull wire ID
Returns
a constant reference to the wire in wireid
Exceptions
cet::exception(category "WireOutOfRange") if no such wire

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 273 of file PlaneGeo.h.

References Wire(), and geo::WireID::Wire.

Referenced by Wire().

273 { return Wire(wireid.Wire); }
WireGeo const & Wire(unsigned int iwire) const
Definition: PlaneGeo.cxx:403
double geo::PlaneGeo::WireCoordinate ( Point_t const &  point) const
inline

Returns the coordinate of the point on the plane, in wire units.

Parameters
pointworld coordinate of the point to get the coordinate of
Returns
the coordinate of the point, in wire pitch units
See also
CoordinateFrom(TVector3 const&, geo::Wire const&)

The method returns the coordinate of the point in the direction measured by the wires on this plane starting on the first wire, in wire units (that is, wire pitches). A point on the first wire will have coordinate 0.0, one on the next wire will have coordinate 1.0, etc.

The point does not need to be on the plane, and the projection of the point to the plane is considered.

Definition at line 704 of file PlaneGeo.h.

References PlaneCoordinate(), and WirePitch().

Referenced by tca::ChgFracBetween(), tca::ChgFracNearEnd(), cluster::MergeClusterAlg::GlobalWire(), lar_cluster3d::PCASeedFinderAlg::LineFit2DHits(), lar_cluster3d::HoughSeedFinderAlg::LineFit2DHits(), tca::MakeBareTP(), tca::MakeTP3D(), lar_cluster3d::StandardHit3DBuilder::NearestWireID(), lar_cluster3d::SnippetHit3DBuilder::NearestWireID(), NearestWireID(), shower::EMShowerAlg::OrderShowerHits_(), trkf::CCTrackMaker::PlnMatch(), tca::PosInPlane(), tca::SetSection(), trkf::TrackLineFitAlg::TrkLineFit(), pma::ProjectionMatchingAlg::validate(), pma::ProjectionMatchingAlg::validate_on_adc(), and pma::ProjectionMatchingAlg::validate_on_adc_test().

705  {
706  return PlaneCoordinate(point) / WirePitch();
707  }
double PlaneCoordinate(Point_t const &point) const
Returns the coordinate of the point on the plane.
Definition: PlaneGeo.h:684
double WirePitch() const
Return the wire pitch (in centimeters). It is assumed constant.
Definition: PlaneGeo.h:312
bool geo::PlaneGeo::WireIDincreasesWithZ ( ) const

Returns whether the higher z wires have higher wire ID.

Returns
whether the higher z wires have higher wire ID
See also
GetIncreasingWireDirection()

This method is related to GetIncreasingWireDirection() (it might be expressed as "GetIncreasingWireDirection()[2] > 0"), but it is implemented in a faster and independent way.

Definition at line 416 of file PlaneGeo.cxx.

References e, GetIncreasingWireDirection(), lar::util::RealComparisons< RealType >::nonNegative(), and geo::Z.

Referenced by PrintPlaneInfo(), and WirePitch().

417  {
419  }
Provides simple real number checks.
constexpr bool nonNegative(Value_t value) const
Returns whether value is larger than or equal() to zero.
Vector_t const & GetIncreasingWireDirection() const
Returns the direction of increasing wires.
Definition: PlaneGeo.h:350
Float_t e
Definition: plot.C:35
auto geo::PlaneGeo::WirePtr ( unsigned int  iwire) const
inline

Returns the wire number iwire from this plane.

Parameters
iwirethe number of local wire
Returns
a constant pointer to the wire, or nullptr if it does not exist

Definition at line 282 of file PlaneGeo.h.

References fWire, and HasWire().

Referenced by GetElementPtr(), Wire(), and geo::WireReadoutGeom::WirePtr().

282 { return HasWire(iwire) ? &fWire[iwire] : nullptr; }
WireCollection_t fWire
List of wires in this plane.
Definition: PlaneGeo.h:1209
bool HasWire(unsigned int iwire) const
Returns whether a wire with index iwire is present in this plane.
Definition: PlaneGeo.h:241
auto geo::PlaneGeo::WirePtr ( WireID const &  wireid) const
inline

Returns the wire in wireid from this plane.

Parameters
wireidfull wire ID
Returns
a constant pointer to the wire, or nullptr if it does not exist

The cryostat, TPC and plane numbers in wireid are ignored, as it is ignored whether wireid is invalid.

Definition at line 293 of file PlaneGeo.h.

References geo::WireID::Wire, and WirePtr().

Referenced by WirePtr().

293 { return WirePtr(wireid.Wire); }
auto WirePtr(unsigned int iwire) const
Returns the wire number iwire from this plane.
Definition: PlaneGeo.h:282

Member Data Documentation

Rect geo::PlaneGeo::fActiveArea
private

Area covered by wires in frame base.

Definition at line 1225 of file PlaneGeo.h.

Referenced by ActiveArea(), DeltaFromActivePlane(), and UpdateActiveArea().

Point_t geo::PlaneGeo::fCenter {}
private

Center of the plane, lying on the wire plane.

Definition at line 1227 of file PlaneGeo.h.

Referenced by GetCenter(), and UpdateWirePlaneCenter().

double geo::PlaneGeo::fCosPhiZ {0.}
private

Cosine of $ \phi_{z} $.

Definition at line 1212 of file PlaneGeo.h.

Referenced by CosPhiZ(), PhiZ(), and UpdatePhiZ().

WidthDepthDecomposer_t geo::PlaneGeo::fDecompFrame {}
private

Decomposition on frame coordinates; the main direction is a "width", the secondary one is just orthogonal to it ("depth"). Normal can differ in sign from the plane one.

Definition at line 1222 of file PlaneGeo.h.

Referenced by ComposePoint(), DecomposePointWidthDepth(), DepthDir(), DetectGeometryDirections(), PointWidthDepthProjection(), PrintPlaneInfo(), UpdateWidthDepthDir(), UpdateWirePlaneCenter(), VectorWidthDepthProjection(), and WidthDir().

WireDecomposer_t geo::PlaneGeo::fDecompWire {}
private

Decomposition on wire coordinates; the main direction is along the wire, the secondary one is the one measured by the wire, the normal matches the plane's normal.

Definition at line 1218 of file PlaneGeo.h.

Referenced by ComposePoint(), ComposeVector(), DecomposePoint(), DistanceFromPlane(), GetIncreasingWireDirection(), GetWireDirection(), InterWireDistance(), PlaneCoordinate(), PlaneCoordinateFrom(), PrintPlaneInfo(), Projection(), ProjectionReferencePoint(), UpdateDecompWireOrigin(), UpdateIncreasingWireDir(), and UpdateWireDir().

RectSpecs geo::PlaneGeo::fFrameSize
private

Size of the frame of the plane.

Definition at line 1223 of file PlaneGeo.h.

Referenced by DeltaFromPlane(), Depth(), DetectGeometryDirections(), MoveProjectionToPlane(), and Width().

PlaneID geo::PlaneGeo::fID
private

ID of this plane.

Definition at line 1229 of file PlaneGeo.h.

Referenced by ID(), and UpdateAfterSorting().

TGeoNode const* geo::PlaneGeo::fNode
private

Node within full geometry.

Definition at line 1205 of file PlaneGeo.h.

Referenced by PlaneGeo(), TPCVolume(), and Volume().

Vector_t geo::PlaneGeo::fNormal
private

Normal to the plane, inward in TPC.

Definition at line 1214 of file PlaneGeo.h.

Referenced by GetNormalDirection(), and UpdatePlaneNormal().

Orient_t geo::PlaneGeo::fOrientation {kVertical}
private

Is the plane vertical or horizontal?

Definition at line 1208 of file PlaneGeo.h.

Referenced by Orientation(), and UpdateOrientation().

double geo::PlaneGeo::fSinPhiZ {0.}
private

Sine of $ \phi_{z} $.

Definition at line 1211 of file PlaneGeo.h.

Referenced by PhiZ(), SinPhiZ(), and UpdatePhiZ().

LocalTransformation_t geo::PlaneGeo::fTrans
private

Plane to world transform.

Definition at line 1206 of file PlaneGeo.h.

Referenced by ComposePoint(), toLocalCoords(), and toWorldCoords().

View_t geo::PlaneGeo::fView {kUnknown}
private

Does this plane measure U, V, or W?

Definition at line 1207 of file PlaneGeo.h.

Referenced by SetView(), and View().

WireCollection_t geo::PlaneGeo::fWire
private

List of wires in this plane.

Definition at line 1209 of file PlaneGeo.h.

Referenced by Depth(), SortWires(), UpdateAfterSorting(), UpdateOrientation(), UpdateWirePitchSlow(), and WirePtr().

double geo::PlaneGeo::fWirePitch {0.}
private

Pitch of wires in this plane.

Definition at line 1210 of file PlaneGeo.h.

Referenced by InterWireDistance(), InterWireProjectedDistance(), UpdateWirePitch(), UpdateWirePitchSlow(), and WirePitch().

constexpr unsigned int geo::PlaneGeo::MaxVerbosity = 6
static

Maximum value for print verbosity.

Definition at line 634 of file PlaneGeo.h.

Referenced by geo::WireReadoutDumper::dumpTPCplane().


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