12 #ifndef ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_    13 #define ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_    19 #include <ecl/config/macros.hpp>    20 #include <ecl/linear_algebra.hpp>    22 #include "../macros.hpp"    29 namespace mobile_robot {
    71         DifferentialDriveKinematics(
    72                         const double &fixed_axis_length,
    73                         const double& wheel_radius) :
    74                 bias(fixed_axis_length),
   113         ecl::Pose2D<double> forwardWithPlatformVelocity(
const double & linearVelocity, 
const double & angularVelocity ) 
const;
   125         ecl::linear_algebra::Vector2d inverse(
const double &linear_velocity, 
const double &angular_velocity) 
const;
   154         ECL_DEPRECATED static ecl::linear_algebra::Vector2d Inverse(
const ecl::linear_algebra::Vector3d &a, 
const ecl::linear_algebra::Vector3d &b);
 #define ECL_DEPRECATED
Deprecated compiler warnings. 
#define ecl_mobile_robot_PUBLIC