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 #include "../macros.hpp"
00026
00027
00028
00029
00030
00031 namespace kobuki {
00032
00033
00034
00035
00036
00037 class kobuki_PUBLIC DiffDrive {
00038 public:
00039 DiffDrive();
00040 const ecl::DifferentialDrive::Kinematics& kinematics() { return diff_drive_kinematics; }
00041 void update(const uint16_t &time_stamp,
00042 const uint16_t &left_encoder,
00043 const uint16_t &right_encoder,
00044 ecl::Pose2D<double> &pose_update,
00045 ecl::linear_algebra::Vector3d &pose_update_rates);
00046 void reset();
00047 void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
00048 double &wheel_right_angle, double &wheel_right_angle_rate);
00049 void setVelocityCommands(const double &vx, const double &wz);
00050 void velocityCommands(const double &vx, const double &wz);
00051 void velocityCommands(const short &cmd_speed, const short &cmd_radius);
00052 void velocityCommands(const std::vector<double> &cmd) { velocityCommands(cmd[0], cmd[1]); }
00053 void velocityCommands(const std::vector<short> &cmd) { velocityCommands(cmd[0], cmd[1]); }
00054
00055
00056
00057
00058 std::vector<short> velocityCommands();
00059 std::vector<double> pointVelocity() const;
00060
00061
00062
00063
00064 double wheel_bias() const { return bias; }
00065
00066 private:
00067 unsigned short last_timestamp;
00068 double last_velocity_left, last_velocity_right;
00069 double last_diff_time;
00070
00071 unsigned short last_tick_left, last_tick_right;
00072 double last_rad_left, last_rad_right;
00073
00074
00075 std::vector<double> point_velocity;
00076 double radius;
00077 double speed;
00078 double bias;
00079 double wheel_radius;
00080 int imu_heading_offset;
00081 const double tick_to_rad;
00082
00083 ecl::DifferentialDrive::Kinematics diff_drive_kinematics;
00084 ecl::Mutex velocity_mutex, state_mutex;
00085
00086
00087 short bound(const double &value);
00088 };
00089
00090 }
00091
00092 #endif