differential_drive.hpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009 ** Ifdefs
00010 *****************************************************************************/
00011 
00012 #ifndef ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_
00013 #define ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_
00014 
00015 /*****************************************************************************
00016 ** Includes
00017 *****************************************************************************/
00018 
00019 #include <ecl/config/macros.hpp>
00020 #include <ecl/linear_algebra.hpp>
00021 #include <ecl/geometry/pose2d.hpp>
00022 
00023 /*****************************************************************************
00024 ** Namespaces
00025 *****************************************************************************/
00026 
00027 namespace ecl {
00028 namespace mobile_robot {
00029 
00030 /*****************************************************************************
00031 ** Interface
00032 *****************************************************************************/
00033 
00062 class DifferentialDriveKinematics {
00063 public:
00070         DifferentialDriveKinematics(
00071                         const double &fixed_axis_length,
00072                         const double& wheel_radius) :
00073                 bias(fixed_axis_length),
00074                 radius(wheel_radius)
00075         {}
00076 
00094         ecl::Pose2D<double> forward(const double &dleft, const double &dright) const;
00095 
00112         ecl::Pose2D<double> forwardWithPlatformVelocity(const double & linearVelocity, const double & angularVelocity ) const;
00113 
00124         ecl::linear_algebra::Vector2d inverse(const double &linear_velocity, const double &angular_velocity) const;
00125 
00153         ECL_DEPRECATED static ecl::linear_algebra::Vector2d Inverse(const ecl::linear_algebra::Vector3d &a, const ecl::linear_algebra::Vector3d &b);
00154 
00182         static ecl::linear_algebra::Vector2d PartialInverse(const ecl::Pose2D<double> &a, const ecl::Pose2D<double> &b);
00183 private:
00184         double bias, radius;
00185 };
00186 
00187 } // namespace mobile_robot
00188 } // namespace ecl
00189 
00190 #endif /* ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_ */


ecl_mobile_robot
Author(s): Daniel Stonier (d.stonier@gmail.com)
autogenerated on Thu Jan 2 2014 11:12:21