Simbody
3.5
|
This is a primitive useful for computations involving a single cubic Bezier curve segment. More...
Public Member Functions | |
CubicBezierCurve_ () | |
Construct an uninitialized curve; control points will be garbage. More... | |
template<int S> | |
CubicBezierCurve_ (const Vec< 4, Vec3P, S > &controlPoints) | |
Construct a cubic Bezier curve using the given control points B=[b0 b1 b2 b3]. More... | |
template<int S> | |
CubicBezierCurve_ (const Row< 4, Vec3P, S > &controlPoints) | |
Alternate signature accepts a Row of control points, although they are stored internally as a Vec. More... | |
const Vec< 4, Vec3P > & | getControlPoints () const |
Return a reference to the Bezier control points B=[b0 b1 b2 b3] that are stored in this object. More... | |
Vec< 4, Vec3P > | calcAlgebraicCoefficients () const |
Calculate the algebraic coefficients A=[a3 a2 a1 a0] from the stored Bezier control points. More... | |
Vec< 4, Vec3P > | calcHermiteCoefficients () const |
Calculate the Hermite (geometric) coefficients H=[h0 h1 hu0 hu1] from the stored Bezier control points. More... | |
Vec3P | evalP (RealP u) const |
Evaluate a point on this curve given a value for parameter u in [0,1]. More... | |
Vec3P | evalPu (RealP u) const |
Evaluate the tangent Pu=dP/du on this curve given a value for parameter u in [0,1]. More... | |
Vec3P | evalPuu (RealP u) const |
Evaluate the second derivative Puu=d2P/du2 on this curve given a value for parameter u in [0,1]. More... | |
Vec3P | evalPuuu (RealP u) const |
Evaluate the third derivative Puuu=d3P/du3 on this curve. More... | |
RealP | calcDsdu (RealP u) const |
Return ds/du, the change in arc length per change in curve parameter. More... | |
UnitVec3P | calcUnitTangent (RealP u) const |
The unit tangent vector t=dP/ds where s is the arc length. More... | |
Vec3P | calcCurvatureVector (RealP u) const |
The curvature vector c=dt/ds where t is the unit tangent vector (t=dP/ds) and s is arclength. More... | |
RealP | calcCurvatureSqr (RealP u) |
Return k^2, the square of the scalar curvature k at the point P(u) on the curve. More... | |
RealP | calcTorsion (RealP u) |
Return tau, the torsion or "second curvature". More... | |
UnitVec3P | calcUnitNormal (RealP u) const |
In our definition, the unit normal vector n points in the "outward" direction, that is, it points away from the center of curvature (opposite the curvature vector). More... | |
RealP | calcCurveFrame (RealP u, TransformP &X_FP) const |
Return the magnitude of the curvature (always positive), and a frame whose origin is a point along the curve, x axis is the outward unit normal n, y is the unit tangent t, and z=x X y is the binormal b, which is a normal to the osculating plane. More... | |
void | split (RealP u, CubicBezierCurve_< P > &left, CubicBezierCurve_< P > &right) const |
Split this curve into two at a point u=t such that 0 < t < 1, such that the first curve coincides with the u=0..t segment of this curve, and the second coincides with the u=t..1 segment. More... | |
void | bisect (CubicBezierCurve_< P > &left, CubicBezierCurve_< P > &right) const |
Split this curve into two at the point u=1/2 (halfway in parameter space, not necessarily in arclength). More... | |
Geo::Sphere_< P > | calcBoundingSphere () const |
Return a sphere that surrounds the entire curve segment in the u=[0..1] range. More... | |
Geo::AlignedBox_< P > | calcAxisAlignedBoundingBox () const |
Return an axis-aligned bounding box (AABB) that surrounds the entire curve segment in the u=[0..1] range. More... | |
Geo::OrientedBox_< P > | calcOrientedBoundingBox () const |
Return an oriented bounding box (OBB) that surrounds the entire curve segment in the u=[0..1] range. More... | |
Static Public Member Functions | |
Utility methods | |
These static methods provide operations useful for working with cubic Bezier curves. See the CubicHermiteCurve_ class for related operations. | |
static Row< 4, P > | calcFb (RealP u) |
Calculate the Bernstein basis functions Fb=[B0..B3] for a given value of the parameter u. More... | |
static Row< 4, P > | calcDFb (RealP u) |
Calculate first derivatives dFb=[B0u..B3u] of the Bernstein basis functions for a given value of the parameter u. More... | |
static Row< 4, P > | calcD2Fb (RealP u) |
Calculate second derivatives d2Fb=[B0uu..B3uu] of the Bernstein basis functions for a given value of the parameter u. More... | |
static Row< 4, P > | calcD3Fb (RealP u) |
Calculate third derivatives d3Fb=[B0uuu..B3uuu] of the Bernstein basis functions for a given value of the parameter u. More... | |
template<int S> | |
static Vec< 4, Vec3P > | calcAFromB (const Vec< 4, Vec3P, S > &B) |
Given the Bezier control points B=~[b0 b1 b2 b3], return the algebraic coefficients A=~[a3 a2 a1 a0]. More... | |
template<int S> | |
static Vec< 4, Vec3P > | calcBFromA (const Vec< 4, Vec3P, S > &A) |
Given the algebraic coefficients A=~[a3 a2 a1 a0], return the Bezier control points B=~[b0 b1 b2 b3]. More... | |
template<int S> | |
static Vec< 4, Vec3P > | calcHFromB (const Vec< 4, Vec3P, S > &B) |
Given the Bezier control points B=~[b0 b1 b2 b3], return the Hermite coefficients H=~[h0 h1 hu0 hu1]. More... | |
template<int S> | |
static Vec< 4, Vec3P > | calcBFromH (const Vec< 4, Vec3P, S > &H) |
Given the Hermite coefficients H=~[h0 h1 hu0 hu1], return the Bezier control points B=~[b0 b1 b2 b3]. More... | |
template<int S> | |
static Vec3P | evalPUsingB (const Vec< 4, Vec3P, S > &B, RealP u) |
Given Bezier control points B and a value for the curve parameter u, return the point P(u) at that location. More... | |
template<int S> | |
static Vec3P | evalPuUsingB (const Vec< 4, Vec3P, S > &B, RealP u) |
Given Bezier control points B and a value for the curve parameter u, return the first derivative Pu(u)=dP/du at that location. More... | |
template<int S> | |
static Vec3P | evalPuuUsingB (const Vec< 4, Vec3P, S > &B, RealP u) |
Given Bezier control points B and a value for the curve parameter u, return the second derivative Puu(u)=d2P/du2 at that location. More... | |
template<int S> | |
static Vec3P | evalPuuuUsingB (const Vec< 4, Vec3P, S > &B, RealP u) |
Given Bezier control points B and a value for the curve parameter u, return the third derivative Puuu(u)=d3P/du3 at that location. More... | |
static Mat< 4, 4, P > | getMb () |
Obtain the Bezier basis matrix Mb explicitly. More... | |
template<int S> | |
static Vec< 4, P > | multiplyByMb (const Vec< 4, P, S > &b) |
Form the product of the Bezier basis matrix Mb and a 4-vector, exploiting the structure of Mb. More... | |
static Mat< 4, 4, P > | getMbInv () |
Obtain the inverse inv(Mb) of the Bezier basis matrix explicitly. More... | |
template<int S> | |
static Vec< 4, P > | multiplyByMbInv (const Vec< 4, P, S > &b) |
Form the product of the inverse inv(Mb) of the Bezier basis matrix Mb and a 4-vector, exploiting the structure of inv(Mb). More... | |
static Mat< 4, 4, P > | getMhInvMb () |
Obtain the product Mh^-1*Mb explicitly; this is the matrix used for conversion from Bezier to Hermite bases since H=Mh^-1 Mb B and is the inverse of the matrix Mb^-1*Mh. More... | |
template<int S> | |
static Vec< 4, P > | multiplyByMhInvMb (const Vec< 4, P, S > &v) |
Given a vector v, form the product inv(Mh)*Mb*v, exploiting the structure of the constant matrix inv(Mh)*Mb (not symmetric). More... | |
static Mat< 4, 4, P > | getMbInvMh () |
Obtain the product Mb^-1*Mh explicitly; this is the matrix used for conversion from Hermite to Bezier bases since B=Mb^-1 Mh H and is the inverse of the matrix Mh^-1*Mb. More... | |
template<int S> | |
static Vec< 4, P > | multiplyByMbInvMh (const Vec< 4, P, S > &v) |
Given a vector v, form the product inv(Mb)*Mh*v, exploiting the structure of the constant matrix inv(Mb)*Mh (not symmetric). More... | |
This is a primitive useful for computations involving a single cubic Bezier curve segment.
Objects of this class contain the Bezier control points, but these can easily be converted to algebraic or Hermite coefficients. A useful feature of the Bezier control points representation is that the curve (not necessarily planar) lies within the convex hull of the four control points. We can use that fact to create a bounding sphere or oriented bounding box around the curve. We can check whether the control points are already convex to ensure that the contained curve is well behaved, and subdivide if not.
Note that a cubic Bezier spline (made up of multiple segments) would not necessarily be composed of these because a spline can be contructed more compactly with shared end points. However, the primitive and inline methods here can be used for fast curve segment computations.
The primary reference for this implementation is the book "Geometric Modeling, 3rd ed." by Michael E. Mortenson, Industrial Press 2006, chapter 4. We follow Mortenson's notation here (with some name changes) and equation numbers are from the text. See CubicHermiteCurve_ comments for an introduction; here we add the Bezier description to the algebraic and Hermite (geometric) forms described there.
The curve is parameterized by a scalar u in [0..1], such that points on the curve, and their derivatives with respect to u are given by
P(u) = B0(u) b0 + B1(u) b1 + B2(u) b2 + B3(u) b3 (4.2) Pu(u) = B0u(u) b0 + B1u(u) b1 + B2u(u) b2 + B3u(u) b3 Puu(u) = B0uu(u) b0 + B1uu(u) b1 + B2uu(u) b2 + B3uu(u) b3 Puuu(u) = B0uuu(u) b0 + B1uuu(u) b1 + B2uuu(u) b2 + B3uuu(u) b3
where the Bi's are the (scalar) Bernstein polynomials given by
B0(u) = (1-u)^3 = -u^3 + 3u^2 - 3u + 1 (4.5) B1(u) = 3 u (1-u)^2 = 3u^3 - 6u^2 + 3u B2(u) = 3 u^2(1-u) = -3u^3 + 3u^2 B3(u) = u^3 = u^3
B0u(u) = -3u^2 + 6u - 3 B0uu(u) = -6u + 6 B0uuu(u) = -6 B1u(u) = 9u^2 - 12u + 3 B1uu(u) = 18u - 12 B1uuu(u) = 18 B2u(u) = -9u^2 + 6u B2uu(u) = -18u + 6 B2uuu(u) = -18 B3u(u) = 3u^2 B3uu(u) = 6u B3uuu(u) = 6
In matrix notation, let Fb=[B0 B1 B2 B3], and U=[u^3 u^2 u 1]. Then Fb = U Mb where Mb, the Bezier basis transformation matrix, and its inverse are:
[ -1 3 -3 1 ] [ 0 0 0 1 ] Mb = [ 3 -6 3 0 ] inv(Mb) = [ 0 0 1/3 1 ] [ -3 3 0 0 ] [ 0 1/3 2/3 1 ] [ 1 0 0 0 ] [ 1 1 1 1 ]
Now we can write the algebraic, Hermite, and Bezier forms in matrix notation. Let A=~[a3 a2 a1 a0], H=~[h0 h1 hu0 hu1], B=~[b0 b1 b2 b3]. We have
P(u) = U A = U Mh H = U Mb B (4.7) A = Mh H = Mb B H = inv(Mh) A = inv(Mh) Mb B (4.8) B = inv(Mb) A = inv(Mb) Mh H (4.9)
where these equations show how to convert among the algebraic, Hermite, and Bezier forms. Note that while U, Fb, Mh, and Mb are ordinary matrices, A, H, and B are hypermatrices since their elements are 3-vectors. Multiplying out the matrix products gives:
[ 1 0 0 0 ] [ 1 0 0 0 ] Mh^-1 Mb = [ 0 0 0 1 ] Mb^-1 Mh = [ 1 0 1/3 0 ] [ -3 3 0 0 ] [ 0 1 0 -1/3 ] [ 0 0 -3 3 ] [ 0 1 0 0 ]
Because of the sparsity of the matrices and the many common subexpressions above, it saves a considerable amount of computation to work out the necessary products by hand, and this implementation does that. For example, to find the Bezier control points B given the Hermite coefficients H, or vice versa, the matrix-vector multiply would take 3x28=84 flops, while the hand-worked versions are:
[h0 ] -1 [ b0 ] [b0] -1 [ h0 ] H = [h1 ] = Mh Mb B = [ b3 ] B = [b1] = Mb Mh H = [h0 + hu0/3] [hu0] [3 (b1-b0)] [b2] [h1 - hu1/3] [hu1] [3 (b3-b2)] [b3] [ h1 ]
which instead take 3x4=12 flops, 7X faster. Conversion between Bezier and algebraic is a little more expensive:
[ b3-b0 + 3 (b1-b2) ] [ a0 ] A = Mb B = [ 3 (b0+b2) - 6 b1 ] B = Mb^-1 A = [ a1/3 + a0 ] [ 3 (b1-b0) ] [ (a2 + 2 a1)/3 + a0 ] [ b0 ] [ a3 + a2 + a1 + a0 ]
which take about 3x10=30 flops, still almost 3X faster than a matrix-vector multiply.
|
inline |
Construct an uninitialized curve; control points will be garbage.
|
inlineexplicit |
Construct a cubic Bezier curve using the given control points B=[b0 b1 b2 b3].
|
inlineexplicit |
|
inline |
Return a reference to the Bezier control points B=[b0 b1 b2 b3] that are stored in this object.
|
inline |
Calculate the algebraic coefficients A=[a3 a2 a1 a0] from the stored Bezier control points.
Cost is 30 flops.
|
inline |
Calculate the Hermite (geometric) coefficients H=[h0 h1 hu0 hu1] from the stored Bezier control points.
Cost is 12 flops.
|
inline |
Evaluate a point on this curve given a value for parameter u in [0,1].
Values outside this range are permitted but do not lie on the curve segment. Cost is 20 flops.
|
inline |
Evaluate the tangent Pu=dP/du on this curve given a value for parameter u in [0,1].
Values outside this range are permitted but do not lie on the curve segment. Cost is 15 flops.
|
inline |
Evaluate the second derivative Puu=d2P/du2 on this curve given a value for parameter u in [0,1].
Values outside this range are permitted but do not lie on the curve segment. Cost is 10 flops.
|
inline |
Evaluate the third derivative Puuu=d3P/du3 on this curve.
Parameter u is ignored here since the 3rd derivative of a cubic curve is a constant. Cost is 3 flops.
|
inline |
Return ds/du, the change in arc length per change in curve parameter.
This is the magnitude of the tangent vector Pu=dP/du. Cost is about 40 flops.
|
inline |
The unit tangent vector t=dP/ds where s is the arc length.
This is undefined at a cusp (Pu(u)==0). Cost is about 55 flops.
|
inline |
The curvature vector c=dt/ds where t is the unit tangent vector (t=dP/ds) and s is arclength.
Cost is about 55 flops.
|
inline |
Return k^2, the square of the scalar curvature k at the point P(u) on the curve.
Curvature is undefined at a cusp (where Pu==0) and is zero at an inflection point (|Pu X Puu|==0). Cost is about 31 flops.
|
inline |
Return tau, the torsion or "second curvature".
Torsion is a signed quantity related to the rate of change of the osculating plane binormal b, with db/ds=tau*n where n is the "outward" unit normal. Torsion is undefined at either a cusp (where Pu==0) or an inflection point (where |Pu X Puu|==0). Cost is about 30 flops.
|
inline |
In our definition, the unit normal vector n points in the "outward" direction, that is, it points away from the center of curvature (opposite the curvature vector).
The normal is undefined at a cusp (Pu(u)==0), and arbitrary at an inflection point (|Pu X Puu|==0). If the curve is a straight line then every point has Puu==0, so the normal is arbitrary everywhere. Cost is about 105 flops.
|
inline |
Return the magnitude of the curvature (always positive), and a frame whose origin is a point along the curve, x axis is the outward unit normal n, y is the unit tangent t, and z=x X y is the binormal b, which is a normal to the osculating plane.
So the vectors n,t,b form a right-handed set; this convention is different from Struik's since he has n pointing the opposite direction. This frame is undefined at a cusp (Pu==0), and the normal is arbitrary at an inflection point (Puu(u)==0) or if the curve is a line (Puu==0 everywhere). Cost is about 160 flops.
|
inline |
Split this curve into two at a point u=t such that 0 < t < 1, such that the first curve coincides with the u=0..t segment of this curve, and the second coincides with the u=t..1 segment.
Each of the new curves is reparameterized so that its curve parameter goes from 0 to 1. This method is only allowed for tol <= t <= 1-tol where tol is the default tolerance for this precision. Cost is 3x15=45 flops.
|
inline |
Split this curve into two at the point u=1/2 (halfway in parameter space, not necessarily in arclength).
This is a faster special case of the split() method. Cost is 3x10=30 flops.
|
inline |
Return a sphere that surrounds the entire curve segment in the u=[0..1] range.
We use the fact that the curve is enclosed within the convex hull of its control points and generate the minimum bounding sphere that includes all four control points.
|
inline |
Return an axis-aligned bounding box (AABB) that surrounds the entire curve segment in the u=[0..1] range.
We use the fact that the curve is enclosed within the convex hull of its control points and generate the minimum axis-aligned box that includes all four control points.
|
inline |
Return an oriented bounding box (OBB) that surrounds the entire curve segment in the u=[0..1] range.
We use the fact that the curve is enclosed within the convex hull of its control points and generate an oriented bounding box that includes all four control points.
|
inlinestatic |
Calculate the Bernstein basis functions Fb=[B0..B3] for a given value of the parameter u.
This is an optimized calculation of U*Mb, taking 9 flops.
|
inlinestatic |
Calculate first derivatives dFb=[B0u..B3u] of the Bernstein basis functions for a given value of the parameter u.
Cost is 10 flops.
|
inlinestatic |
Calculate second derivatives d2Fb=[B0uu..B3uu] of the Bernstein basis functions for a given value of the parameter u.
Cost is 5 flops.
|
inlinestatic |
Calculate third derivatives d3Fb=[B0uuu..B3uuu] of the Bernstein basis functions for a given value of the parameter u.
For a cubic curve this is just a constant. Cost is 0 flops.
|
inlinestatic |
Given the Bezier control points B=~[b0 b1 b2 b3], return the algebraic coefficients A=~[a3 a2 a1 a0].
All coefficients are 3-vectors. Cost is 30 flops.
|
inlinestatic |
Given the algebraic coefficients A=~[a3 a2 a1 a0], return the Bezier control points B=~[b0 b1 b2 b3].
All coefficients are 3-vectors. Cost is 27 flops.
|
inlinestatic |
Given the Bezier control points B=~[b0 b1 b2 b3], return the Hermite coefficients H=~[h0 h1 hu0 hu1].
All coefficients are 3-vectors. Cost is 12 flops.
|
inlinestatic |
Given the Hermite coefficients H=~[h0 h1 hu0 hu1], return the Bezier control points B=~[b0 b1 b2 b3].
All coefficients are 3-vectors. Cost is 12 flops.
|
inlinestatic |
Given Bezier control points B and a value for the curve parameter u, return the point P(u) at that location.
Cost is 30 flops. Note that if you need to do this for the same curve more than twice, it is cheaper to convert to algebraic form using calcAFromB() (30 flops) and then evaluate using A (20 flops).
|
inlinestatic |
Given Bezier control points B and a value for the curve parameter u, return the first derivative Pu(u)=dP/du at that location.
Cost is 31 flops. Note that if you need to do this for the same curve more than once, it is cheaper to convert to algebraic form using calcAFromB() (30 flops) and then evaluate using A (15 flops).
|
inlinestatic |
Given Bezier control points B and a value for the curve parameter u, return the second derivative Puu(u)=d2P/du2 at that location.
Cost is 26 flops. Note that if you need to do this for the same curve more than once, it is cheaper to convert to algebraic form using calcAFromB() (30 flops) and then evaluate using A (10 flops).
|
inlinestatic |
Given Bezier control points B and a value for the curve parameter u, return the third derivative Puuu(u)=d3P/du3 at that location.
Cost is 21 flops. Note that if you need to do this for the same curve more than once, it is cheaper to convert to algebraic form using calcAFromB() (30 flops) and then evaluate using A (3 flops).
|
inlinestatic |
Obtain the Bezier basis matrix Mb explicitly.
This is mostly useful for testing since specialized routines can save a lot of CPU time over working directly in matrix form. This is a constant matrix so there is no computation cost. The matrix is symmetric although we return a full 4x4 here.
|
inlinestatic |
Form the product of the Bezier basis matrix Mb and a 4-vector, exploiting the structure of Mb.
Since Mb is symmetric you can also use this for multiplication by a row from the left, i.e. ~b*Mb=~(~Mb*b)=~(Mb*b). Cost is 10 flops.
|
inlinestatic |
Obtain the inverse inv(Mb) of the Bezier basis matrix explicitly.
This is mostly useful for testing since specialized routines can save a lot of CPU time over working directly in matrix form. This is a constant matrix so there is no computation cost. The matrix is symmetric although we return a full 4x4 here.
|
inlinestatic |
Form the product of the inverse inv(Mb) of the Bezier basis matrix Mb and a 4-vector, exploiting the structure of inv(Mb).
Since inv(Mb) is symmetric you can also use this for multiplication by a row from the left, i.e. ~b*Mb^-1=~(Mb^-T*b)=~(Mb^-1*b). Cost is 9 flops.
|
inlinestatic |
Obtain the product Mh^-1*Mb explicitly; this is the matrix used for conversion from Bezier to Hermite bases since H=Mh^-1 Mb B and is the inverse of the matrix Mb^-1*Mh.
This is mostly useful for testing since specialized routines can save a lot of CPU time over working directly in matrix form. There is a very efficient method for forming matrix-vector products with this matrix. This is a constant matrix so there is no computation cost.
|
inlinestatic |
Given a vector v, form the product inv(Mh)*Mb*v, exploiting the structure of the constant matrix inv(Mh)*Mb (not symmetric).
Cost is 4 flops.
|
inlinestatic |
Obtain the product Mb^-1*Mh explicitly; this is the matrix used for conversion from Hermite to Bezier bases since B=Mb^-1 Mh H and is the inverse of the matrix Mh^-1*Mb.
This matrix is not symmetric. This method is mostly useful for testing since specialized routines can save a lot of CPU time over working directly in matrix form. There is a very efficient method for forming matrix-vector products with this matrix. This is a constant matrix so there is no computation cost here.
|
inlinestatic |
Given a vector v, form the product inv(Mb)*Mh*v, exploiting the structure of the constant matrix inv(Mb)*Mh (not symmetric).
Cost is 4 flops.