16 #include "../../../include/ecl/mobile_robot/kinematics/differential_drive.hpp"    23 namespace mobile_robot {
    30 using ecl::linear_algebra::Vector2d;
    31 using ecl::linear_algebra::Vector3d;
    32 using ecl::linear_algebra::Rotation2D;
    40   LegacyPose2D<double> pose_update;
    41   double ds = radius*(dleft+dright)/2.0;
    42   double domega = radius*(dright-dleft)/bias;
    45   pose_update.translation(ds, 0);
    46   pose_update.rotation(domega);
    50 ecl::LegacyPose2D<double> DifferentialDriveKinematics::forwardWithPlatformVelocity(
const double & linearVelocity, 
const double & angularVelocity )
 const    55   pose_update.translation(linearVelocity, 0);
    56   pose_update.rotation(angularVelocity);
    60 Vector2d DifferentialDriveKinematics::inverse(
const double &linear_velocity, 
const double &angular_velocity)
 const {
    64         double right = (2*linear_velocity+angular_velocity*bias)/(2*radius);
    65         double left = 2*linear_velocity/radius - right;
    74   diff << b.x() - a.x(), b.y() - a.y();
    77   Vector2d dr = a.rotationMatrix().inverse()*diff;
    78   double ds = sqrt(dr(0)*dr(0)+dr(1)*dr(1));
    82   double dtheta = b.heading() - a.heading(); 
    86   return (diff << ds, dtheta).finished();
    91 Vector2d DifferentialDriveKinematics::Inverse(
const Vector3d &a, 
const Vector3d &b) {
    96         dxy << poseb.x() - posea.x(), poseb.y() - posea.y();
    99         Rotation2D<double> rotation(-posea.heading());
   100         Vector2d dr = rotation*dxy;
   103         double ds = sqrt(dr(0)*dr(0)+dr(1)*dr(1));
   107         double dtheta = b[2] - a[2]; 
 
ecl_geometry_PUBLIC const float & wrap_angle(float &angle)