Go to the documentation of this file.00001
00009
00010
00011
00012
00013 #ifndef KOBUKI_DIFF_DRIVE_HPP_
00014 #define KOBUKI_DIFF_DRIVE_HPP_
00015
00016
00017
00018
00019
00020 #include <vector>
00021 #include <climits>
00022 #include <stdint.h>
00023 #include <ecl/mobile_robot.hpp>
00024 #include <ecl/threads/mutex.hpp>
00025
00026
00027
00028
00029
00030 namespace kobuki {
00031
00032
00033
00034
00035
00036 class DiffDrive {
00037 public:
00038 DiffDrive();
00039 const ecl::DifferentialDrive::Kinematics& kinematics() { return diff_drive_kinematics; }
00040 void update(const uint16_t &time_stamp,
00041 const uint16_t &left_encoder,
00042 const uint16_t &right_encoder,
00043 ecl::Pose2D<double> &pose_update,
00044 ecl::linear_algebra::Vector3d &pose_update_rates);
00045 void reset(const double& current_heading);
00046 void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
00047 double &wheel_right_angle, double &wheel_right_angle_rate);
00048 void setVelocityCommands(const double &vx, const double &wz);
00049 void velocityCommands(const double &vx, const double &wz);
00050 void velocityCommands(const short &cmd_speed, const short &cmd_radius);
00051 void velocityCommands(const std::vector<double> &cmd) { velocityCommands(cmd[0], cmd[1]); }
00052 void velocityCommands(const std::vector<short> &cmd) { velocityCommands(cmd[0], cmd[1]); }
00053
00054
00055
00056
00057 std::vector<short> velocityCommands();
00058
00059 double linearVelocity() const { return point_velocity[0]; }
00060 double angularVelocity() const { return point_velocity[1]; }
00061 std::vector<double> pointVelocity() const { return point_velocity; }
00062
00063
00064
00065
00066 double wheel_bias() const { return bias; }
00067
00068 private:
00069 unsigned short last_timestamp;
00070 double last_velocity_left, last_velocity_right;
00071 double last_diff_time;
00072
00073 unsigned short last_tick_left, last_tick_right;
00074 double last_rad_left, last_rad_right;
00075
00076
00077 std::vector<double> point_velocity;
00078 double radius;
00079 double speed;
00080 double bias;
00081 double wheel_radius;
00082 int imu_heading_offset;
00083 const double tick_to_rad;
00084
00085 ecl::DifferentialDrive::Kinematics diff_drive_kinematics;
00086 ecl::Mutex velocity_mutex, state_mutex;
00087
00088
00089 short bound(const double &value);
00090 };
00091
00092 }
00093
00094 #endif