diff_drive.cpp
Go to the documentation of this file.
1 
10 /*****************************************************************************
11 ** Includes
12 *****************************************************************************/
13 
14 #include "../../include/kobuki_driver/modules/diff_drive.hpp"
15 
16 /*****************************************************************************
17 ** Namespaces
18 *****************************************************************************/
19 
20 namespace kobuki {
21 
22 /*****************************************************************************
23 ** Implementation
24 *****************************************************************************/
26  last_velocity_left(0.0),
27  last_velocity_right(0.0),
28  last_tick_left(0),
29  last_tick_right(0),
30  last_rad_left(0.0),
31  last_rad_right(0.0),
32 // v(0.0), w(0.0), // command velocities, in [m/s] and [rad/s]
33  point_velocity(2,0.0), // command velocities, in [m/s] and [rad/s]
34  radius(0.0), // command velocities, in [mm] and [mm/s]
35  speed(0.0),
36  bias(0.23), // wheelbase, wheel_to_wheel, in [m]
37  wheel_radius(0.035), // radius of main wheel, in [m]
38  tick_to_rad(0.002436916871363930187454f),
39  diff_drive_kinematics(bias, wheel_radius)
40 {
41  (void) imu_heading_offset;
42 }
43 
55 void DiffDrive::update(const uint16_t &time_stamp,
56  const uint16_t &left_encoder,
57  const uint16_t &right_encoder,
58  ecl::LegacyPose2D<double> &pose_update,
59  ecl::linear_algebra::Vector3d &pose_update_rates) {
60  state_mutex.lock();
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;
70  if (!init_l)
71  {
72  last_tick_left = curr_tick_left;
73  init_l = true;
74  }
75  left_diff_ticks = (double)(short)((curr_tick_left - last_tick_left) & 0xffff);
76  last_tick_left = curr_tick_left;
77  last_rad_left += tick_to_rad * left_diff_ticks;
78 
79  curr_tick_right = right_encoder;
80  if (!init_r)
81  {
82  last_tick_right = curr_tick_right;
83  init_r = true;
84  }
85  right_diff_ticks = (double)(short)((curr_tick_right - last_tick_right) & 0xffff);
86  last_tick_right = curr_tick_right;
87  last_rad_right += tick_to_rad * right_diff_ticks;
88 
89  // TODO this line and the last statements are really ugly; refactor, put in another place
90  pose_update = diff_drive_kinematics.forward(tick_to_rad * left_diff_ticks, tick_to_rad * right_diff_ticks);
91 
92  if (curr_timestamp != last_timestamp)
93  {
94  last_diff_time = ((double)(short)((curr_timestamp - last_timestamp) & 0xffff)) / 1000.0f;
95  last_timestamp = curr_timestamp;
96  last_velocity_left = (tick_to_rad * left_diff_ticks) / last_diff_time;
97  last_velocity_right = (tick_to_rad * right_diff_ticks) / last_diff_time;
98  } else {
99  // we need to set the last_velocity_xxx to zero?
100  }
101 
102  pose_update_rates << pose_update.x()/last_diff_time,
103  pose_update.y()/last_diff_time,
104  pose_update.heading()/last_diff_time;
105  state_mutex.unlock();
106 }
107 
109  state_mutex.lock();
110  last_rad_left = 0.0;
111  last_rad_right = 0.0;
112  last_velocity_left = 0.0;
113  last_velocity_right = 0.0;
114  state_mutex.unlock();
115 }
116 
117 void DiffDrive::getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate,
118  double &wheel_right_angle, double &wheel_right_angle_rate) {
119  state_mutex.lock();
120  wheel_left_angle = last_rad_left;
121  wheel_right_angle = last_rad_right;
122  wheel_left_angle_rate = last_velocity_left;
123  wheel_right_angle_rate = last_velocity_right;
124  state_mutex.unlock();
125 }
126 
127 void DiffDrive::setVelocityCommands(const double &vx, const double &wz) {
128  // vx: in m/s
129  // wz: in rad/s
130  std::vector<double> cmd_vel;
131  cmd_vel.push_back(vx);
132  cmd_vel.push_back(wz);
133  point_velocity = cmd_vel;
134 }
135 
136 void DiffDrive::velocityCommands(const double &vx, const double &wz) {
137  // vx: in m/s
138  // wz: in rad/s
139  velocity_mutex.lock();
140  const double epsilon = 0.0001;
141 
142  // Special Case #1 : Straight Run
143  if( std::abs(wz) < epsilon ) {
144  radius = 0.0f;
145  speed = 1000.0f * vx;
146  velocity_mutex.unlock();
147  return;
148  }
149 
150  radius = vx * 1000.0f / wz;
151  // Special Case #2 : Pure Rotation or Radius is less than or equal to 1.0 mm
152  if( std::abs(vx) < epsilon || std::abs(radius) <= 1.0f ) {
153  speed = 1000.0f * bias * wz / 2.0f;
154  radius = 1.0f;
155  velocity_mutex.unlock();
156  return;
157  }
158 
159  // General Case :
160  if( radius > 0.0f ) {
161  speed = (radius + 1000.0f * bias / 2.0f) * wz;
162  } else {
163  speed = (radius - 1000.0f * bias / 2.0f) * wz;
164  }
165  velocity_mutex.unlock();
166  return;
167 }
168 
169 void DiffDrive::velocityCommands(const short &cmd_speed, const short &cmd_radius) {
170  velocity_mutex.lock();
171  speed = static_cast<double>(cmd_speed); // In [mm/s]
172  radius = static_cast<double>(cmd_radius); // In [mm]
173  velocity_mutex.unlock();
174  return;
175 }
176 
177 std::vector<short> DiffDrive::velocityCommands() {
178  velocity_mutex.lock();
179  std::vector<short> cmd(2);
180  cmd[0] = bound(speed); // In [mm/s]
181  cmd[1] = bound(radius); // In [mm]
182  velocity_mutex.unlock();
183  return cmd;
184 }
185 
186 std::vector<double> DiffDrive::pointVelocity() const {
187  return point_velocity;
188 }
189 
190 short DiffDrive::bound(const double &value) {
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);
194 }
195 
196 } // namespace kobuki
double radius
short bound(const double &value)
Definition: diff_drive.cpp:190
ecl::Mutex velocity_mutex
Definition: diff_drive.hpp:85
std::vector< double > point_velocity
Definition: diff_drive.hpp:76
ecl::Mutex state_mutex
Definition: diff_drive.hpp:85
double speed
unsigned short last_tick_left
Definition: diff_drive.hpp:72
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
Definition: diff_drive.cpp:117
const double tick_to_rad
Definition: diff_drive.hpp:82
ecl::DifferentialDrive::Kinematics diff_drive_kinematics
Definition: diff_drive.hpp:84
double bias
std::vector< double > pointVelocity() const
Definition: diff_drive.cpp:186
std::vector< short > velocityCommands()
Definition: diff_drive.cpp:177
unsigned short last_timestamp
Definition: diff_drive.hpp:68
double last_velocity_left
Definition: diff_drive.hpp:69
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.
Definition: diff_drive.cpp:55
void f(int i) ecl_debug_throw_decl(StandardException)
unsigned short last_tick_right
Definition: diff_drive.hpp:72
double last_velocity_right
Definition: diff_drive.hpp:69
void setVelocityCommands(const double &vx, const double &wz)
Definition: diff_drive.cpp:127


kobuki_driver
Author(s): Daniel Stonier , Younghun Ju , Jorge Santos Simon
autogenerated on Fri Sep 18 2020 03:22:01