35 #include <Eigen/Dense> 38 using namespace Eigen;
40 typedef std::pair<double, double>
Point;
43 const double pi = 3.141592653589793238463;
48 LshapeTracker(
const double& x_corner,
const double& y_corner,
const double& L1,
const double& L2,
const double& theta,
const double& dt);
50 void update(
const double& thetaL1,
const double& x_corner,
const double& y_corner,
const double& L1,
const double& L2,
const double& dt,
const int cluster_size);
51 void BoxModel(
double& x,
double& y,
double& vx,
double& vy,
double& theta,
double& psi,
double& omega,
double& L1,
double& L2,
double&
length,
double& width);
56 double x_old,
y_old, L1_old, L2_old, old_thetaL1;
61 void ClockwisePointSwitch();
62 void CounterClockwisePointSwitch();
63 double findTurn(
const double& new_angle,
const double& old_angle);
64 void detectCornerPointSwitch(
const double& from,
const double& to,
const double dt);
65 void detectCornerPointSwitchMahalanobis(
const double& from,
const double& to,
const double dt);
66 void detectCornerPointSwitchMahalanobis(
const double& from,
const double& to,
const double L1,
const double L2,
const double x_corner,
const double y_corner);
77 void findOrientation(
double& psi,
double& length,
double& width);
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
std::pair< double, double > Point
Eigen::Matrix< double, 6, 1 > Vector6d