Program Listing for File differential_drive.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_mobile_robot/include/ecl/mobile_robot/kinematics/differential_drive.hpp)

/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_
#define ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

#include <ecl/config/macros.hpp>
#include <ecl/linear_algebra.hpp>
#include "../macros.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ecl {

namespace mobile_robot {

/*****************************************************************************
** Interface
*****************************************************************************/

class ecl_mobile_robot_PUBLIC DifferentialDriveKinematics {
public:
    DifferentialDriveKinematics(
            const double& fixed_axis_length,
            const double& wheel_radius) :
        bias(fixed_axis_length),
        radius(wheel_radius)
    {}

    ecl::linear_algebra::Vector3d poseUpdateFromWheelDifferential(
      const double& dleft,
      const double &dright
    ) const;

    ecl::linear_algebra::Vector3d poseUpdateFromBaseDifferential(
      const double& translation,
      const double& rotation
    ) const;

    ecl::linear_algebra::Vector2d baseToWheelVelocities(
      const double& linear_velocity,
      const double& angular_velocity
    ) const;

    static ecl::linear_algebra::Vector2d PoseToBaseDifferential(
        const ecl::linear_algebra::Vector3d &a,
        const ecl::linear_algebra::Vector3d &b
    );
private:
    double bias, radius;
};

} // namespace mobile_robot
} // namespace ecl

#endif /* ECL_MOBILE_ROBOT_DIFFERENTIAL_DRIVE_KINEMATICS_HPP_ */