14 #include "../../include/kobuki_driver/modules/diff_drive.hpp" 26 last_velocity_left(0.0),
27 last_velocity_right(0.0),
33 point_velocity(2,0.0),
38 tick_to_rad(0.002436916871363930187454
f),
39 diff_drive_kinematics(
bias, wheel_radius)
56 const uint16_t &left_encoder,
57 const uint16_t &right_encoder,
59 ecl::linear_algebra::Vector3d &pose_update_rates) {
61 static bool init_l =
false;
62 static bool init_r =
false;
63 double left_diff_ticks = 0.0f;
64 double right_diff_ticks = 0.0f;
65 unsigned short curr_tick_left = 0;
66 unsigned short curr_tick_right = 0;
67 unsigned short curr_timestamp = 0;
68 curr_timestamp = time_stamp;
69 curr_tick_left = left_encoder;
75 left_diff_ticks = (double)(
short)((curr_tick_left -
last_tick_left) & 0xffff);
79 curr_tick_right = right_encoder;
85 right_diff_ticks = (double)(
short)((curr_tick_right -
last_tick_right) & 0xffff);
118 double &wheel_right_angle,
double &wheel_right_angle_rate) {
130 std::vector<double> cmd_vel;
131 cmd_vel.push_back(vx);
132 cmd_vel.push_back(wz);
140 const double epsilon = 0.0001;
143 if( std::abs(wz) < epsilon ) {
145 speed = 1000.0f * vx;
150 radius = vx * 1000.0f / wz;
152 if( std::abs(vx) < epsilon || std::abs(
radius) <= 1.0
f ) {
171 speed =
static_cast<double>(cmd_speed);
172 radius =
static_cast<double>(cmd_radius);
179 std::vector<short> cmd(2);
191 if (value > static_cast<double>(SHRT_MAX))
return SHRT_MAX;
192 if (value < static_cast<double>(SHRT_MIN))
return SHRT_MIN;
193 return static_cast<short>(value);
short bound(const double &value)
ecl::Mutex velocity_mutex
std::vector< double > point_velocity
unsigned short last_tick_left
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
ecl::DifferentialDrive::Kinematics diff_drive_kinematics
std::vector< double > pointVelocity() const
std::vector< short > velocityCommands()
unsigned short last_timestamp
double last_velocity_left
void update(const uint16_t &time_stamp, const uint16_t &left_encoder, const uint16_t &right_encoder, ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
Updates the odometry from firmware stamps and encoders.
void f(int i) ecl_debug_throw_decl(StandardException)
unsigned short last_tick_right
double last_velocity_right
void setVelocityCommands(const double &vx, const double &wz)