31#define assert(e) ((void)0)
40 #define IMETHOD __forceinline
43 #define IMETHOD inline
54 #define FRAMES_CHECKI(a) assert(a)
56 #define FRAMES_CHECKI(a)
85 #pragma warning (disable:4786)
87 inline double sin(
double a) {
91 inline double cos(
double a) {
94 inline double exp(
double a) {
97 inline double log(
double a) {
100 inline double tan(
double a) {
124 inline double pow(
double a,
double b) {
182extern const double PI;
203inline double max(
double a,
double b) {
211inline double min(
double a,
double b) {
223 #define INLINE __forceinline
226 #define INLINE inline
231 double beta,
double b ) {
232 return alfa*a+
beta*
b;
250inline double sign(
double arg) {
251 return (arg<0)?(-1):(1);
254inline double sqr(
double arg) {
return arg*arg;}
255inline double Norm(
double arg) {
256 return fabs( (
double)arg );
260#if defined(__WIN32__) && !defined(__GNUC__)
261inline double hypot(
double y,
double x) { return ::_hypot(
y,
x);}
262inline double abs(
double x) { return ::fabs(
x);}
271 return ((
eps>tmp)&& (tmp>-
eps) );
275 a = 1.98*rand()/(double)RAND_MAX -0.99;
279 a = 0.001+0.99*rand()/(double)RAND_MAX;
282inline double diff(
double a,
double b,
double dt) {
288inline double addDelta(
double a,
double da,
double dt) {
const T & Arg
Arg is used for passing the element to a function.
ccl_device_inline float beta(const float x, const float y)
ccl_device_inline float2 fabs(const float2 a)
ccl_device_inline float3 atan2(const float3 y, const float3 x)
IMETHOD Vector diff(const Vector &a, const Vector &b, double dt=1)
INLINE S Norm(const Rall1d< T, V, S > &value)
const double deg2rad
the value pi/180
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE void SetToIdentity(Rall1d< T, V, S > &value)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
const double rad2deg
the value 180/pi
INLINE Rall1d< T, V, S > LinComb(S alfa, const Rall1d< T, V, S > &a, const T &beta, const Rall1d< T, V, S > &b)
int MAXLENFILENAME
maximal length of a file name
const double PI
the value of pi
IMETHOD bool Equal(const VectorAcc &, const VectorAcc &, double=epsilon)
int VSIZE
the number of derivatives used in the RN-... objects.
double epsilon2
power or 2 of epsilon
IMETHOD Vector addDelta(const Vector &a, const Vector &da, double dt=1)
INLINE void LinCombR(S alfa, const Rall1d< T, V, S > &a, const T &beta, const Rall1d< T, V, S > &b, Rall1d< T, V, S > &result)
IMETHOD void random(Vector &a)
addDelta operator for displacement rotational velocity.
IMETHOD void SetToZero(Vector &v)
IMETHOD void posrandom(Vector &a)
double epsilon
default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001.