@@ -851,57 +851,74 @@ def qslerp(
851
851
def _compute_cdf_sin_squared (theta : float ):
852
852
"""
853
853
Computes the CDF for the distribution of angular magnitude for uniformly sampled rotations.
854
-
854
+
855
855
:arg theta: angular magnitude
856
856
:rtype: float
857
857
:return: cdf of a given angular magnitude
858
858
:rtype: float
859
859
860
- Helper function for uniform sampling of rotations with constrained angular magnitude.
860
+ Helper function for uniform sampling of rotations with constrained angular magnitude.
861
861
This function returns the integral of the pdf of angular magnitudes (2/pi * sin^2(theta/2)).
862
862
"""
863
863
return (theta - np .sin (theta )) / np .pi
864
864
865
+
865
866
@lru_cache (maxsize = 1 )
866
- def _generate_inv_cdf_sin_squared_interp (num_interpolation_points : int = 256 ) -> interpolate .interp1d :
867
+ def _generate_inv_cdf_sin_squared_interp (
868
+ num_interpolation_points : int = 256 ,
869
+ ) -> interpolate .interp1d :
867
870
"""
868
871
Computes an interpolation function for the inverse CDF of the distribution of angular magnitude.
869
-
872
+
870
873
:arg num_interpolation_points: number of points to use in the interpolation function
871
874
:rtype: int
872
875
:return: interpolation function for the inverse cdf of a given angular magnitude
873
876
:rtype: interpolate.interp1d
874
877
875
- Helper function for uniform sampling of rotations with constrained angular magnitude.
876
- This function returns interpolation function for the inverse of the integral of the
878
+ Helper function for uniform sampling of rotations with constrained angular magnitude.
879
+ This function returns interpolation function for the inverse of the integral of the
877
880
pdf of angular magnitudes (2/pi * sin^2(theta/2)), which is not analytically defined.
878
881
"""
879
882
cdf_sin_squared_interp_angles = np .linspace (0 , np .pi , num_interpolation_points )
880
- cdf_sin_squared_interp_values = _compute_cdf_sin_squared (cdf_sin_squared_interp_angles )
881
- return interpolate .interp1d (cdf_sin_squared_interp_values , cdf_sin_squared_interp_angles )
883
+ cdf_sin_squared_interp_values = _compute_cdf_sin_squared (
884
+ cdf_sin_squared_interp_angles
885
+ )
886
+ return interpolate .interp1d (
887
+ cdf_sin_squared_interp_values , cdf_sin_squared_interp_angles
888
+ )
889
+
882
890
883
- def _compute_inv_cdf_sin_squared (x : ArrayLike , num_interpolation_points : int = 256 ) -> ArrayLike :
891
+ def _compute_inv_cdf_sin_squared (
892
+ x : ArrayLike , num_interpolation_points : int = 256
893
+ ) -> ArrayLike :
884
894
"""
885
895
Computes the inverse CDF of the distribution of angular magnitude.
886
-
896
+
887
897
:arg x: value for cdf of angular magnitudes
888
898
:rtype: ArrayLike
889
899
:arg num_interpolation_points: number of points to use in the interpolation function
890
900
:rtype: int
891
901
:return: angular magnitude associate with cdf value
892
902
:rtype: ArrayLike
893
903
894
- Helper function for uniform sampling of rotations with constrained angular magnitude.
895
- This function returns the angle associated with the cdf value derived form integral of
904
+ Helper function for uniform sampling of rotations with constrained angular magnitude.
905
+ This function returns the angle associated with the cdf value derived form integral of
896
906
the pdf of angular magnitudes (2/pi * sin^2(theta/2)), which is not analytically defined.
897
907
"""
898
- inv_cdf_sin_squared_interp = _generate_inv_cdf_sin_squared_interp (num_interpolation_points )
908
+ inv_cdf_sin_squared_interp = _generate_inv_cdf_sin_squared_interp (
909
+ num_interpolation_points
910
+ )
899
911
return inv_cdf_sin_squared_interp (x )
900
912
901
- def qrand (theta_range :Optional [ArrayLike2 ] = None , unit : str = "rad" , num_interpolation_points : int = 256 ) -> UnitQuaternionArray :
913
+
914
+ def qrand (
915
+ theta_range : Optional [ArrayLike2 ] = None ,
916
+ unit : str = "rad" ,
917
+ num_interpolation_points : int = 256 ,
918
+ ) -> UnitQuaternionArray :
902
919
"""
903
920
Random unit-quaternion
904
-
921
+
905
922
:arg theta_range: angular magnitude range [min,max], defaults to None.
906
923
:type xrange: 2-element sequence, optional
907
924
:arg unit: angular units: 'rad' [default], or 'deg'
@@ -913,7 +930,7 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
913
930
:return: random unit-quaternion
914
931
:rtype: ndarray(4)
915
932
916
- Computes a uniformly distributed random unit-quaternion, with in a maximum
933
+ Computes a uniformly distributed random unit-quaternion, with in a maximum
917
934
angular magnitude, which can be considered equivalent to a random SO(3) rotation.
918
935
919
936
.. runblock:: pycon
@@ -924,24 +941,30 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
924
941
if theta_range is not None :
925
942
theta_range = getunit (theta_range , unit )
926
943
927
- if (theta_range [0 ] < 0 or theta_range [1 ] > np .pi or theta_range [0 ] > theta_range [1 ]):
928
- ValueError ('Invalid angular range. Must be within the range[0, pi].'
929
- + f' Recieved { theta_range } .' )
944
+ if (
945
+ theta_range [0 ] < 0
946
+ or theta_range [1 ] > np .pi
947
+ or theta_range [0 ] > theta_range [1 ]
948
+ ):
949
+ ValueError (
950
+ "Invalid angular range. Must be within the range[0, pi]."
951
+ + f" Recieved { theta_range } ."
952
+ )
953
+
954
+ # Sample axis and angle independently, respecting the CDF of the
955
+ # angular magnitude under uniform sampling.
930
956
931
- # Sample axis and angle independently, respecting the CDF of the
932
- # angular magnitude under uniform sampling.
933
-
934
- # Sample angle using inverse transform sampling based on CDF
957
+ # Sample angle using inverse transform sampling based on CDF
935
958
# of the angular distribution (2/pi * sin^2(theta/2))
936
959
theta = _compute_inv_cdf_sin_squared (
937
960
np .random .uniform (
938
- low = _compute_cdf_sin_squared (theta_range [0 ]),
961
+ low = _compute_cdf_sin_squared (theta_range [0 ]),
939
962
high = _compute_cdf_sin_squared (theta_range [1 ]),
940
963
),
941
964
num_interpolation_points = num_interpolation_points ,
942
965
)
943
966
# Sample axis uniformly using 3D normal distributed
944
- v = np .random .randn (3 )
967
+ v = np .random .randn (3 )
945
968
v /= np .linalg .norm (v )
946
969
947
970
return np .r_ [math .cos (theta / 2 ), (math .sin (theta / 2 ) * v )]
@@ -953,7 +976,7 @@ def qrand(theta_range:Optional[ArrayLike2] = None, unit: str = "rad", num_interp
953
976
math .sqrt (u [0 ]) * math .sin (2 * math .pi * u [2 ]),
954
977
math .sqrt (u [0 ]) * math .cos (2 * math .pi * u [2 ]),
955
978
]
956
-
979
+
957
980
958
981
def qmatrix (q : ArrayLike4 ) -> R4x4 :
959
982
"""
0 commit comments