kinematics/differential_drive.hpp
Go to the documentation of this file.
1 
8 /*****************************************************************************
9 ** Ifdefs
10 *****************************************************************************/
11 
12 #ifndef ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_
13 #define ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_
14 
15 /*****************************************************************************
16 ** Includes
17 *****************************************************************************/
18 
19 #include <ecl/config/macros.hpp>
20 #include <ecl/linear_algebra.hpp>
21 #include <ecl/geometry/pose2d.hpp>
22 #include "../macros.hpp"
23 
24 /*****************************************************************************
25 ** Namespaces
26 *****************************************************************************/
27 
28 namespace ecl {
29 namespace mobile_robot {
30 
31 /*****************************************************************************
32 ** Interface
33 *****************************************************************************/
34 
63 class ecl_mobile_robot_PUBLIC DifferentialDriveKinematics {
64 public:
71  DifferentialDriveKinematics(
72  const double &fixed_axis_length,
73  const double& wheel_radius) :
74  bias(fixed_axis_length),
75  radius(wheel_radius)
76  {}
77 
95  ecl::Pose2D<double> forward(const double &dleft, const double &dright) const;
96 
113  ecl::Pose2D<double> forwardWithPlatformVelocity(const double & linearVelocity, const double & angularVelocity ) const;
114 
125  ecl::linear_algebra::Vector2d inverse(const double &linear_velocity, const double &angular_velocity) const;
126 
154  ECL_DEPRECATED static ecl::linear_algebra::Vector2d Inverse(const ecl::linear_algebra::Vector3d &a, const ecl::linear_algebra::Vector3d &b);
155 
183  static ecl::linear_algebra::Vector2d PartialInverse(const ecl::Pose2D<double> &a, const ecl::Pose2D<double> &b);
184 private:
185  double bias, radius;
186 };
187 
188 } // namespace mobile_robot
189 } // namespace ecl
190 
191 #endif /* ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_ */
#define ECL_DEPRECATED
Deprecated compiler warnings.
#define ecl_mobile_robot_PUBLIC
double radius
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
double bias


xbot_node
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:28:13