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


ecl_mobile_robot
Author(s): Daniel Stonier
autogenerated on Thu Nov 10 2016 03:52:36