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 #include "../macros.hpp"
00023 
00024 /*****************************************************************************
00025 ** Namespaces
00026 *****************************************************************************/
00027 
00028 namespace ecl {
00029 namespace mobile_robot {
00030 
00031 /*****************************************************************************
00032 ** Interface
00033 *****************************************************************************/
00034 
00063 class ecl_mobile_robot_PUBLIC DifferentialDriveKinematics {
00064 public:
00071         DifferentialDriveKinematics(
00072                         const double &fixed_axis_length,
00073                         const double& wheel_radius) :
00074                 bias(fixed_axis_length),
00075                 radius(wheel_radius)
00076         {}
00077 
00095         ecl::Pose2D<double> forward(const double &dleft, const double &dright) const;
00096 
00113         ecl::Pose2D<double> forwardWithPlatformVelocity(const double & linearVelocity, const double & angularVelocity ) const;
00114 
00125         ecl::linear_algebra::Vector2d inverse(const double &linear_velocity, const double &angular_velocity) const;
00126 
00154         ECL_DEPRECATED static ecl::linear_algebra::Vector2d Inverse(const ecl::linear_algebra::Vector3d &a, const ecl::linear_algebra::Vector3d &b);
00155 
00183         static ecl::linear_algebra::Vector2d PartialInverse(const ecl::Pose2D<double> &a, const ecl::Pose2D<double> &b);
00184 private:
00185         double bias, radius;
00186 };
00187 
00188 } // namespace mobile_robot
00189 } // namespace ecl
00190 
00191 #endif /* ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_ */


ecl_mobile_robot
Author(s): Daniel Stonier
autogenerated on Fri Aug 28 2015 10:34:58