45 const static double EPS = 1e-5;
141 ROS_ERROR(
"Caster joint \"%s\" not calibrated (namespace: %s)",
169 ROS_ERROR(
"The Base controller could not start because the casters were not calibrated. Relaunch the base controller after you see the caster calibration finish.");
175 ROS_ERROR(
"BaseController: could not configure velocity filters for casters");
179 ROS_ERROR(
"BaseController: could not configure velocity filters for wheels");
190 double vel_mag = sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
194 cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
195 cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
205 ROS_DEBUG(
"BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
207 ROS_DEBUG(
"BaseController:: clamped vel: %f", clamped_vel_mag);
208 ROS_DEBUG(
"BaseController:: vel: %f", vel_mag);
223 geometry_msgs::Twist result;
224 geometry_msgs::Twist alpha;
225 double delta(0), max_delta(0);
227 delta = end.linear.x -
start.linear.x;
228 max_delta = max_rate.linear.x * dT;
229 if(fabs(delta) <= max_delta || max_delta <
EPS)
232 alpha.linear.x = max_delta / fabs(delta);
234 delta = end.linear.y -
start.linear.y;
235 max_delta = max_rate.linear.y * dT;
236 if(fabs(delta) <= max_delta || max_delta <
EPS)
239 alpha.linear.y = max_delta / fabs(delta);
241 delta = end.angular.z -
start.angular.z;
242 max_delta = max_rate.angular.z * dT;
243 if(fabs(delta) <= max_delta || max_delta <
EPS)
246 alpha.angular.z = max_delta / fabs(delta);
248 double alpha_min = alpha.linear.x;
249 if(alpha.linear.y < alpha_min)
250 alpha_min = alpha.linear.y;
251 if(alpha.angular.z < alpha_min)
252 alpha_min = alpha.angular.z;
254 result.linear.x =
start.linear.x + alpha_min * (end.linear.x -
start.linear.x);
255 result.linear.y =
start.linear.y + alpha_min * (end.linear.y -
start.linear.y);
256 result.angular.z =
start.angular.z + alpha_min * (end.angular.z -
start.angular.z);
262 geometry_msgs::Twist cmd_vel;
264 cmd_vel.linear.x =
cmd_vel_.linear.x;
265 cmd_vel.linear.y =
cmd_vel_.linear.y;
266 cmd_vel.angular.z =
cmd_vel_.angular.z;
383 geometry_msgs::Twist result;
385 double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
386 double error_steer(0.0), error_steer_m_pi(0.0);
404 steer_angle_desired = atan2(result.linear.y, result.linear.x);
410 steer_angle_desired);
413 steer_angle_desired_m_pi);
415 if(fabs(error_steer_m_pi) < fabs(error_steer))
417 error_steer = error_steer_m_pi;
418 steer_angle_desired = steer_angle_desired_m_pi;
439 geometry_msgs::Twist wheel_point_velocity;
440 geometry_msgs::Twist wheel_point_velocity_projected;
441 geometry_msgs::Twist wheel_caster_steer_component;
442 geometry_msgs::Twist caster_2d_velocity;
444 caster_2d_velocity.linear.x = 0;
445 caster_2d_velocity.linear.y = 0;
446 caster_2d_velocity.angular.z = 0;
454 double steer_angle_actual = 0;
464 double costh = cos(-steer_angle_actual);
465 double sinth = sin(-steer_angle_actual);
467 wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
468 wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;