45 const static double EPS = 1e-5;
140 ROS_ERROR(
"Caster joint \"%s\" not calibrated (namespace: %s)",
167 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.");
173 ROS_ERROR(
"BaseController: could not configure velocity filters for casters");
183 double vel_mag = sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
187 cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
188 cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
198 ROS_DEBUG(
"BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
200 ROS_DEBUG(
"BaseController:: clamped vel: %f", clamped_vel_mag);
201 ROS_DEBUG(
"BaseController:: vel: %f", vel_mag);
214 geometry_msgs::Twist
Pr2BaseController::interpolateCommand(
const geometry_msgs::Twist &start,
const geometry_msgs::Twist &end,
const geometry_msgs::Twist &max_rate,
const double &dT)
216 geometry_msgs::Twist result;
217 geometry_msgs::Twist alpha;
218 double delta(0), max_delta(0);
220 delta = end.linear.x -
start.linear.x;
221 max_delta = max_rate.linear.x * dT;
222 if(fabs(delta) <= max_delta || max_delta <
EPS)
225 alpha.linear.x = max_delta / fabs(delta);
227 delta = end.linear.y -
start.linear.y;
228 max_delta = max_rate.linear.y * dT;
229 if(fabs(delta) <= max_delta || max_delta <
EPS)
232 alpha.linear.y = max_delta / fabs(delta);
234 delta = end.angular.z -
start.angular.z;
235 max_delta = max_rate.angular.z * dT;
236 if(fabs(delta) <= max_delta || max_delta <
EPS)
239 alpha.angular.z = max_delta / fabs(delta);
241 double alpha_min = alpha.linear.x;
242 if(alpha.linear.y < alpha_min)
243 alpha_min = alpha.linear.y;
244 if(alpha.angular.z < alpha_min)
245 alpha_min = alpha.angular.z;
247 result.linear.x =
start.linear.x + alpha_min * (end.linear.x -
start.linear.x);
248 result.linear.y =
start.linear.y + alpha_min * (end.linear.y -
start.linear.y);
249 result.angular.z =
start.angular.z + alpha_min * (end.angular.z -
start.angular.z);
255 geometry_msgs::Twist cmd_vel;
257 cmd_vel.linear.x =
cmd_vel_.linear.x;
258 cmd_vel.linear.y =
cmd_vel_.linear.y;
259 cmd_vel.angular.z =
cmd_vel_.angular.z;
375 geometry_msgs::Twist result;
377 double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
378 double error_steer(0.0), error_steer_m_pi(0.0);
396 steer_angle_desired = atan2(result.linear.y, result.linear.x);
402 steer_angle_desired);
405 steer_angle_desired_m_pi);
407 if(fabs(error_steer_m_pi) < fabs(error_steer))
409 error_steer = error_steer_m_pi;
410 steer_angle_desired = steer_angle_desired_m_pi;
431 geometry_msgs::Twist wheel_point_velocity;
432 geometry_msgs::Twist wheel_point_velocity_projected;
433 geometry_msgs::Twist wheel_caster_steer_component;
434 geometry_msgs::Twist caster_2d_velocity;
436 caster_2d_velocity.linear.x = 0;
437 caster_2d_velocity.linear.y = 0;
438 caster_2d_velocity.angular.z = 0;
440 double steer_angle_actual = 0;
444 caster_2d_velocity.angular.z =
base_kin_.
wheel_[
i].parent_->steer_velocity_desired_;
449 double costh = cos(-steer_angle_actual);
450 double sinth = sin(-steer_angle_actual);
452 wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
453 wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;
454 base_kin_.
wheel_[
i].wheel_speed_cmd_ = (wheel_point_velocity_projected.linear.x + wheel_caster_steer_component.linear.x) / (
base_kin_.
wheel_[i].wheel_radius_);