Package org.robwork.sdurw
Class DistanceStrategyResult
- java.lang.Object
-
- org.robwork.sdurw.DistanceStrategyResult
-
public class DistanceStrategyResult extends java.lang.Object
-
-
Constructor Summary
Constructors Constructor Description DistanceStrategyResult()
DistanceStrategyResult(long cPtr, boolean cMemoryOwn)
-
Method Summary
All Methods Static Methods Instance Methods Concrete Methods Modifier and Type Method Description void
clear()
void
delete()
ProximityModelPtr
getA()
pointer to the ProximityModel containing the geometries for the first frameProximityModelPtr
getB()
pointer to the ProximityModel containing the geometries for the second framestatic long
getCPtr(DistanceStrategyResult obj)
double
getDistance()
distance between frame f1 and frame f1Frame
getF1()
reference to the first frameFrame
getF2()
reference to the second frameint
getGeoIdxA()
geometry index to triangle mesh Aint
getGeoIdxB()
geometry index to triangle mesh Blong
getIdx1()
index to the first face/triangle that is the closest featurelong
getIdx2()
index to the second face/triangle that is the closest featureVector3Dd
getP1()
Closest point on f1 to f2, described in f1 reference frameVector3Dd
getP2()
Closest point on f2 to f1, described in f1 reference framevoid
setA(ProximityModelPtr value)
pointer to the ProximityModel containing the geometries for the first framevoid
setB(ProximityModelPtr value)
pointer to the ProximityModel containing the geometries for the second framevoid
setDistance(double value)
distance between frame f1 and frame f1void
setF1(Frame value)
reference to the first framevoid
setF2(Frame value)
reference to the second framevoid
setGeoIdxA(int value)
geometry index to triangle mesh Avoid
setGeoIdxB(int value)
geometry index to triangle mesh Bvoid
setIdx1(long value)
index to the first face/triangle that is the closest featurevoid
setIdx2(long value)
index to the second face/triangle that is the closest featurevoid
setP1(Vector3Dd value)
Closest point on f1 to f2, described in f1 reference framevoid
setP2(Vector3Dd value)
Closest point on f2 to f1, described in f1 reference framejava.lang.String
toString()
-
-
-
Method Detail
-
getCPtr
public static long getCPtr(DistanceStrategyResult obj)
-
delete
public void delete()
-
setF1
public void setF1(Frame value)
reference to the first frame
-
getF1
public Frame getF1()
reference to the first frame
-
setF2
public void setF2(Frame value)
reference to the second frame
-
getF2
public Frame getF2()
reference to the second frame
-
setA
public void setA(ProximityModelPtr value)
pointer to the ProximityModel containing the geometries for the first frame
-
getA
public ProximityModelPtr getA()
pointer to the ProximityModel containing the geometries for the first frame
-
setB
public void setB(ProximityModelPtr value)
pointer to the ProximityModel containing the geometries for the second frame
-
getB
public ProximityModelPtr getB()
pointer to the ProximityModel containing the geometries for the second frame
-
setP1
public void setP1(Vector3Dd value)
Closest point on f1 to f2, described in f1 reference frame
-
getP1
public Vector3Dd getP1()
Closest point on f1 to f2, described in f1 reference frame
-
setP2
public void setP2(Vector3Dd value)
Closest point on f2 to f1, described in f1 reference frame
-
getP2
public Vector3Dd getP2()
Closest point on f2 to f1, described in f1 reference frame
-
setDistance
public void setDistance(double value)
distance between frame f1 and frame f1
-
getDistance
public double getDistance()
distance between frame f1 and frame f1
-
setGeoIdxA
public void setGeoIdxA(int value)
geometry index to triangle mesh A
-
getGeoIdxA
public int getGeoIdxA()
geometry index to triangle mesh A
-
setGeoIdxB
public void setGeoIdxB(int value)
geometry index to triangle mesh B
-
getGeoIdxB
public int getGeoIdxB()
geometry index to triangle mesh B
-
setIdx1
public void setIdx1(long value)
index to the first face/triangle that is the closest feature
-
getIdx1
public long getIdx1()
index to the first face/triangle that is the closest feature
-
setIdx2
public void setIdx2(long value)
index to the second face/triangle that is the closest feature
-
getIdx2
public long getIdx2()
index to the second face/triangle that is the closest feature
-
clear
public void clear()
-
toString
public java.lang.String toString()
- Overrides:
toString
in classjava.lang.Object
-
-