13 #ifndef KOBUKI_DIFF_DRIVE_HPP_
14 #define KOBUKI_DIFF_DRIVE_HPP_
26 #include "../macros.hpp"
42 void update(
const uint16_t &time_stamp,
43 const uint16_t &left_encoder,
44 const uint16_t &right_encoder,
46 ecl::linear_algebra::Vector3d &pose_update_rates);
48 void getWheelJointStates(
double &wheel_left_angle,
double &wheel_left_angle_rate,
49 double &wheel_right_angle,
double &wheel_right_angle_rate);
50 void setVelocityCommands(
const double &vx,
const double &wz);
51 void velocityCommands(
const double &vx,
const double &wz);
52 void velocityCommands(
const short &cmd_speed,
const short &cmd_radius);
53 void velocityCommands(
const std::vector<double> &cmd) { velocityCommands(cmd[0], cmd[1]); }
54 void velocityCommands(
const std::vector<short> &cmd) { velocityCommands(cmd[0], cmd[1]); }
59 std::vector<short> velocityCommands();
60 std::vector<double> pointVelocity()
const;
65 double wheel_bias()
const {
return bias; }
68 unsigned short last_timestamp;
69 double last_velocity_left, last_velocity_right;
70 double last_diff_time;
72 unsigned short last_tick_left, last_tick_right;
73 double last_rad_left, last_rad_right;
76 std::vector<double> point_velocity;
81 int imu_heading_offset;
82 const double tick_to_rad;
85 ecl::Mutex velocity_mutex, state_mutex;
88 short bound(
const double &value);