00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include "safe_base_controller/pr2_base_controller2_safe.h"
00041 #include "pluginlib/class_list_macros.h"
00042
00043 PLUGINLIB_DECLARE_CLASS(safe_base_controller, Pr2BaseController2Safe, controller::Pr2BaseController2Safe, pr2_controller_interface::Controller)
00044
00045 namespace controller {
00046
00047 const static double EPS = 1e-5;
00048
00049 Pr2BaseController2Safe::Pr2BaseController2Safe()
00050 {
00051
00052 cmd_vel_.linear.x = 0;
00053 cmd_vel_.linear.y = 0;
00054 cmd_vel_.angular.z = 0;
00055
00056 desired_vel_.linear.x = 0;
00057 desired_vel_.linear.y = 0;
00058 desired_vel_.angular.z = 0;
00059
00060 cmd_vel_t_.linear.x = 0;
00061 cmd_vel_t_.linear.y = 0;
00062 cmd_vel_t_.angular.z = 0;
00063
00064 safe_max_x_ = 0;
00065 safe_min_x_ = 0;
00066 safe_max_y_ = 0;
00067 safe_min_y_ = 0;
00068 safe_max_z_ = 0;
00069 safe_min_z_ = 0;
00070
00071 new_cmd_available_ = false;
00072 last_publish_time_ = ros::Time(0.0);
00073
00074 pthread_mutex_init(&pr2_base_controller_lock_, NULL);
00075 }
00076
00077 Pr2BaseController2Safe::~Pr2BaseController2Safe()
00078 {
00079 cmd_sub_.shutdown();
00080 cmd_sub_deprecated_.shutdown();
00081 sub_cmd_limits.shutdown();
00082 }
00083
00084 bool Pr2BaseController2Safe::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00085 {
00086 if(!base_kinematics_.init(robot,n))
00087 return false;
00088 node_ = n;
00089 state_publisher_.reset(new realtime_tools::RealtimePublisher<pr2_mechanism_controllers::BaseControllerState2>(n, base_kinematics_.name_ + "/state", 1));
00090
00091 int num_joints = base_kinematics_.num_wheels_ + base_kinematics_.num_casters_;
00092 state_publisher_->msg_.joint_names.resize((size_t)num_joints);
00093 state_publisher_->msg_.joint_velocity_measured.resize((size_t)num_joints);
00094 state_publisher_->msg_.joint_effort_measured.resize((size_t)num_joints);
00095 state_publisher_->msg_.joint_command.resize((size_t)num_joints);
00096 state_publisher_->msg_.joint_effort_commanded.resize((size_t)num_joints);
00097 state_publisher_->msg_.joint_error.resize((size_t)num_joints);
00098 state_publisher_->msg_.joint_effort_error.resize((size_t)num_joints);
00099
00100
00101 node_.param<double> ("max_translational_velocity", max_translational_velocity_,0.5);
00102 node_.param<double> ("max_rotational_velocity", max_rotational_velocity_, 10.0);
00103 node_.param<double> ("max_translational_acceleration/x", max_accel_.linear.x, .2);
00104 node_.param<double> ("max_translational_acceleration/y", max_accel_.linear.y, .2);
00105 node_.param<double> ("max_rotational_acceleration", max_accel_.angular.z, 10.0);
00106
00107 node_.param<double> ("kp_caster_steer", kp_caster_steer_, 80.0);
00108 node_.param<double> ("timeout_vel_limits", timeout_vel_limits_, 1.0);
00109 node_.param<double> ("timeout", timeout_, 1.0);
00110 node_.param<double> ("state_publish_rate", state_publish_rate_,2.0);
00111 if(state_publish_rate_ <= 0.0)
00112 {
00113 publish_state_ = false;
00114 state_publish_time_ = 0.0;
00115 }
00116 else
00117 {
00118 publish_state_ = true;
00119 state_publish_time_ = 1.0/state_publish_rate_;
00120 }
00121
00122
00123 cmd_sub_ = node_.subscribe<geometry_msgs::Twist>("command", 1, &Pr2BaseController2Safe::commandCallback, this);
00124
00125
00126 caster_controller_.resize(base_kinematics_.num_casters_);
00127 caster_position_pid_.resize(base_kinematics_.num_casters_);
00128 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00129 {
00130 control_toolbox::Pid p_i_d;
00131 state_publisher_->msg_.joint_names[i] = base_kinematics_.caster_[i].joint_name_;
00132 if(!p_i_d.init(ros::NodeHandle(node_, base_kinematics_.caster_[i].joint_name_+"/velocity_controller")))
00133 {
00134 ROS_ERROR("Could not initialize pid for %s",base_kinematics_.caster_[i].joint_name_.c_str());
00135 return false;
00136 }
00137
00138 if(!caster_position_pid_[i].init(ros::NodeHandle(node_, base_kinematics_.caster_[i].joint_name_+"/position_controller")))
00139 {
00140 ROS_ERROR("Could not initialize position pid controller for %s",base_kinematics_.caster_[i].joint_name_.c_str());
00141 return false;
00142 }
00143 caster_controller_[i].reset(new JointVelocityController());
00144 if(!caster_controller_[i]->init(base_kinematics_.robot_state_, base_kinematics_.caster_[i].joint_name_, p_i_d))
00145 {
00146 ROS_ERROR("Could not initialize pid for %s",base_kinematics_.caster_[i].joint_name_.c_str());
00147 return false;
00148 }
00149 if (!caster_controller_[i]->joint_state_->calibrated_)
00150 {
00151 ROS_ERROR("Caster joint \"%s\" not calibrated (namespace: %s)",
00152 base_kinematics_.caster_[i].joint_name_.c_str(), node_.getNamespace().c_str());
00153 return false;
00154 }
00155 }
00156
00157 wheel_pid_controllers_.resize(base_kinematics_.num_wheels_);
00158
00159 for(int j = 0; j < base_kinematics_.num_wheels_; j++)
00160 {
00161 control_toolbox::Pid p_i_d;
00162 state_publisher_->msg_.joint_names[j + base_kinematics_.num_casters_] = base_kinematics_.wheel_[j].joint_name_;
00163 if(!wheel_pid_controllers_[j].init(ros::NodeHandle(node_,base_kinematics_.wheel_[j].joint_name_)))
00164 {
00165 ROS_ERROR("Could not initialize pid for %s",base_kinematics_.wheel_[j].joint_name_.c_str());
00166 return false;
00167 }
00168
00169
00170
00171
00172
00173
00174 }
00175 for(int i = 0; i < base_kinematics_.num_casters_; ++i)
00176 {
00177 if(!base_kinematics_.caster_[i].joint_->calibrated_)
00178 {
00179 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.");
00180 return false;
00181 }
00182 }
00183
00184 if (!((filters::MultiChannelFilterBase<double>&)caster_vel_filter_).configure(base_kinematics_.num_casters_, std::string("caster_velocity_filter"), node_)){
00185 ROS_ERROR("BaseController: could not configure velocity filters for casters");
00186 return false;
00187 }
00188 if (!((filters::MultiChannelFilterBase<double>&)wheel_vel_filter_).configure(base_kinematics_.num_wheels_, std::string("wheel_velocity_filter"), node_)){
00189 ROS_ERROR("BaseController: could not configure velocity filters for wheels");
00190 return false;
00191 }
00192 filtered_velocity_.resize(base_kinematics_.num_casters_);
00193 filtered_wheel_velocity_.resize(base_kinematics_.num_wheels_);
00194
00195
00196 sub_cmd_limits = node_.subscribe("command_limits", 1, &Pr2BaseController2Safe::cmdLimitsCB, this);
00197 paused_ = false;
00198
00199 ROS_INFO("SAFE base controller of type 'pr2_base_controller2_safe' successfully initialized.");
00200 return true;
00201 }
00202
00203
00204 void Pr2BaseController2Safe::setCommand(const geometry_msgs::Twist &cmd_vel)
00205 {
00206 double vel_mag = sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
00207 double clamped_vel_mag = filters::clamp(vel_mag,-max_translational_velocity_, max_translational_velocity_);
00208 if(vel_mag > EPS)
00209 {
00210 cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
00211 cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
00212 }
00213 else
00214 {
00215 cmd_vel_t_.linear.x = 0.0;
00216 cmd_vel_t_.linear.y = 0.0;
00217 }
00218 cmd_vel_t_.angular.z = filters::clamp(cmd_vel.angular.z, -max_rotational_velocity_, max_rotational_velocity_);
00219 cmd_received_timestamp_ = base_kinematics_.robot_state_->getTime();
00220
00221 ROS_DEBUG("BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
00222 ROS_DEBUG("BaseController:: command current: %f %f %f", cmd_vel_.linear.x,cmd_vel_.linear.y,cmd_vel_.angular.z);
00223 ROS_DEBUG("BaseController:: clamped vel: %f", clamped_vel_mag);
00224 ROS_DEBUG("BaseController:: vel: %f", vel_mag);
00225
00226 for(int i=0; i < (int) base_kinematics_.num_wheels_; i++)
00227 {
00228 ROS_DEBUG("BaseController:: wheel speed cmd:: %d %f",i,(base_kinematics_.wheel_[i].direction_multiplier_*base_kinematics_.wheel_[i].wheel_speed_cmd_));
00229 }
00230 for(int i=0; i < (int) base_kinematics_.num_casters_; i++)
00231 {
00232 ROS_DEBUG("BaseController:: caster speed cmd:: %d %f",i,(base_kinematics_.caster_[i].steer_velocity_desired_));
00233 }
00234 new_cmd_available_ = true;
00235 }
00236
00237 geometry_msgs::Twist Pr2BaseController2Safe::interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT)
00238 {
00239 geometry_msgs::Twist result;
00240 geometry_msgs::Twist alpha;
00241 double delta(0), max_delta(0);
00242
00243 delta = end.linear.x - start.linear.x;
00244 max_delta = max_rate.linear.x * dT;
00245 if(fabs(delta) <= max_delta || max_delta < EPS)
00246 alpha.linear.x = 1;
00247 else
00248 alpha.linear.x = max_delta / fabs(delta);
00249
00250 delta = end.linear.y - start.linear.y;
00251 max_delta = max_rate.linear.y * dT;
00252 if(fabs(delta) <= max_delta || max_delta < EPS)
00253 alpha.linear.y = 1;
00254 else
00255 alpha.linear.y = max_delta / fabs(delta);
00256
00257 delta = end.angular.z - start.angular.z;
00258 max_delta = max_rate.angular.z * dT;
00259 if(fabs(delta) <= max_delta || max_delta < EPS)
00260 alpha.angular.z = 1;
00261 else
00262 alpha.angular.z = max_delta / fabs(delta);
00263
00264 double alpha_min = alpha.linear.x;
00265 if(alpha.linear.y < alpha_min)
00266 alpha_min = alpha.linear.y;
00267 if(alpha.angular.z < alpha_min)
00268 alpha_min = alpha.angular.z;
00269
00270 result.linear.x = start.linear.x + alpha_min * (end.linear.x - start.linear.x);
00271 result.linear.y = start.linear.y + alpha_min * (end.linear.y - start.linear.y);
00272 result.angular.z = start.angular.z + alpha_min * (end.angular.z - start.angular.z);
00273 return result;
00274 }
00275
00276 geometry_msgs::Twist Pr2BaseController2Safe::getCommand()
00277 {
00278 geometry_msgs::Twist cmd_vel;
00279 pthread_mutex_lock(&pr2_base_controller_lock_);
00280 cmd_vel.linear.x = cmd_vel_.linear.x;
00281 cmd_vel.linear.y = cmd_vel_.linear.y;
00282 cmd_vel.angular.z = cmd_vel_.angular.z;
00283 pthread_mutex_unlock(&pr2_base_controller_lock_);
00284 return cmd_vel;
00285 }
00286
00287 void Pr2BaseController2Safe::starting()
00288 {
00289 last_time_ = base_kinematics_.robot_state_->getTime();
00290 cmd_received_timestamp_ = base_kinematics_.robot_state_->getTime();
00291 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00292 {
00293 caster_controller_[i]->starting();
00294 }
00295 for(int j = 0; j < base_kinematics_.num_wheels_; j++)
00296 {
00297
00298 }
00299 }
00300
00301 void Pr2BaseController2Safe::update()
00302 {
00303 ros::Time current_time = base_kinematics_.robot_state_->getTime();
00304 double dT = std::min<double>((current_time - last_time_).toSec(), base_kinematics_.MAX_DT_);
00305
00306 if(new_cmd_available_)
00307 {
00308 if(pthread_mutex_trylock(&pr2_base_controller_lock_) == 0)
00309 {
00310 desired_vel_.linear.x = cmd_vel_t_.linear.x;
00311 desired_vel_.linear.y = cmd_vel_t_.linear.y;
00312 desired_vel_.angular.z = cmd_vel_t_.angular.z;
00313 new_cmd_available_ = false;
00314 pthread_mutex_unlock(&pr2_base_controller_lock_);
00315 }
00316 }
00317
00318
00319 if( (current_time - cmd_received_timestamp_).toSec() > timeout_
00320 || (current_time - cmd_limits_timestamp_).toSec() > timeout_vel_limits_ )
00321 {
00322 cmd_vel_.linear.x = 0;
00323 cmd_vel_.linear.y = 0;
00324 cmd_vel_.angular.z = 0;
00325
00326
00327
00328 }
00329 else
00330 cmd_vel_ = interpolateCommand(cmd_vel_, desired_vel_, max_accel_, dT);
00331
00332
00333
00334
00335
00336 cmd_vel_.linear.x = std::min(std::max(cmd_vel_.linear.x, safe_min_x_), safe_max_x_);
00337 cmd_vel_.linear.y = std::min(std::max(cmd_vel_.linear.y, safe_min_y_), safe_max_y_);
00338 cmd_vel_.angular.z = std::min(std::max(cmd_vel_.angular.z, safe_min_z_), safe_max_z_);
00339
00340
00341
00342
00343 computeJointCommands(dT);
00344
00345 setJointCommands();
00346
00347 updateJointControllers();
00348
00349 if(publish_state_)
00350 publishState(current_time);
00351
00352 last_time_ = current_time;
00353
00354 }
00355
00356 void Pr2BaseController2Safe::publishState(const ros::Time &time)
00357 {
00358 if((time - last_publish_time_).toSec() < state_publish_time_)
00359 {
00360 return;
00361 }
00362
00363 if(state_publisher_->trylock())
00364 {
00365 state_publisher_->msg_.command.linear.x = cmd_vel_.linear.x;
00366 state_publisher_->msg_.command.linear.y = cmd_vel_.linear.y;
00367 state_publisher_->msg_.command.angular.z = cmd_vel_.angular.z;
00368
00369 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00370 {
00371 state_publisher_->msg_.joint_names[i] = base_kinematics_.caster_[i].joint_name_;
00372 state_publisher_->msg_.joint_velocity_measured[i] = base_kinematics_.caster_[i].joint_->velocity_;
00373 state_publisher_->msg_.joint_command[i]= base_kinematics_.caster_[i].steer_angle_desired_;
00374 state_publisher_->msg_.joint_error[i] = base_kinematics_.caster_[i].joint_->position_ - base_kinematics_.caster_[i].steer_angle_desired_;
00375
00376 state_publisher_->msg_.joint_effort_measured[i] = base_kinematics_.caster_[i].joint_->measured_effort_;
00377 state_publisher_->msg_.joint_effort_commanded[i] = base_kinematics_.caster_[i].joint_->commanded_effort_;
00378 state_publisher_->msg_.joint_effort_error[i] = base_kinematics_.caster_[i].joint_->measured_effort_ - base_kinematics_.caster_[i].joint_->commanded_effort_;
00379 }
00380 for(int i = 0; i < base_kinematics_.num_wheels_; i++)
00381 {
00382 state_publisher_->msg_.joint_names[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].joint_name_;
00383 state_publisher_->msg_.joint_velocity_measured[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].joint_->velocity_;
00384 state_publisher_->msg_.joint_command[i+base_kinematics_.num_casters_]= base_kinematics_.wheel_[i].joint_->velocity_-base_kinematics_.wheel_[i].wheel_speed_cmd_;
00385 state_publisher_->msg_.joint_error[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].wheel_speed_cmd_;
00386
00387 state_publisher_->msg_.joint_effort_measured[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].joint_->measured_effort_;
00388 state_publisher_->msg_.joint_effort_commanded[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].joint_->commanded_effort_;
00389 state_publisher_->msg_.joint_effort_error[i+base_kinematics_.num_casters_] = base_kinematics_.wheel_[i].joint_->measured_effort_ - base_kinematics_.wheel_[i].joint_->commanded_effort_;
00390 }
00391 state_publisher_->unlockAndPublish();
00392 last_publish_time_ = time;
00393 }
00394 }
00395
00396 void Pr2BaseController2Safe::computeJointCommands(const double &dT)
00397 {
00398 base_kinematics_.computeWheelPositions();
00399
00400 computeDesiredCasterSteer(dT);
00401
00402 computeDesiredWheelSpeeds(dT);
00403 }
00404
00405 void Pr2BaseController2Safe::setJointCommands()
00406 {
00407 setDesiredCasterSteer();
00408
00409 setDesiredWheelSpeeds();
00410 }
00411
00412 void Pr2BaseController2Safe::computeDesiredCasterSteer(const double &dT)
00413 {
00414 geometry_msgs::Twist result;
00415
00416 double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
00417 double error_steer(0.0), error_steer_m_pi(0.0);
00418 double trans_vel = sqrt(cmd_vel_.linear.x * cmd_vel_.linear.x + cmd_vel_.linear.y * cmd_vel_.linear.y);
00419
00420 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00421 {
00422 filtered_velocity_[i] = base_kinematics_.caster_[i].joint_->velocity_;
00423 }
00424 caster_vel_filter_.update(filtered_velocity_,filtered_velocity_);
00425
00426 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00427 {
00428 result = base_kinematics_.pointVel2D(base_kinematics_.caster_[i].offset_, cmd_vel_);
00429 if(trans_vel < EPS && fabs(cmd_vel_.angular.z) < EPS)
00430 {
00431 steer_angle_desired = base_kinematics_.caster_[i].steer_angle_stored_;
00432 }
00433 else
00434 {
00435 steer_angle_desired = atan2(result.linear.y, result.linear.x);
00436 base_kinematics_.caster_[i].steer_angle_stored_ = steer_angle_desired;
00437 }
00438 steer_angle_desired_m_pi = angles::normalize_angle(steer_angle_desired + M_PI);
00439 error_steer = angles::shortest_angular_distance(steer_angle_desired, base_kinematics_.caster_[i].joint_->position_);
00440 error_steer_m_pi = angles::shortest_angular_distance(steer_angle_desired_m_pi, base_kinematics_.caster_[i].joint_->position_);
00441
00442 if(fabs(error_steer_m_pi) < fabs(error_steer))
00443 {
00444 error_steer = error_steer_m_pi;
00445 steer_angle_desired = steer_angle_desired_m_pi;
00446 }
00447 base_kinematics_.caster_[i].steer_angle_desired_ = steer_angle_desired;
00448
00449
00450 double command = caster_position_pid_[i].updatePid(error_steer,filtered_velocity_[i],ros::Duration(dT));
00451 base_kinematics_.caster_[i].joint_->commanded_effort_ = command;
00452
00453 base_kinematics_.caster_[i].caster_position_error_ = error_steer;
00454 }
00455 }
00456
00457 void Pr2BaseController2Safe::setDesiredCasterSteer()
00458 {
00459 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00460 {
00461
00462 }
00463 }
00464
00465 void Pr2BaseController2Safe::computeDesiredWheelSpeeds(const double &dT)
00466 {
00467 geometry_msgs::Twist wheel_point_velocity;
00468 geometry_msgs::Twist wheel_point_velocity_projected;
00469 geometry_msgs::Twist wheel_caster_steer_component;
00470 geometry_msgs::Twist caster_2d_velocity;
00471
00472 caster_2d_velocity.linear.x = 0;
00473 caster_2d_velocity.linear.y = 0;
00474 caster_2d_velocity.angular.z = 0;
00475
00476 for(int i = 0; i < base_kinematics_.num_casters_; i++)
00477 {
00478 filtered_wheel_velocity_[i] = base_kinematics_.wheel_[i].joint_->velocity_;
00479 }
00480 wheel_vel_filter_.update(filtered_wheel_velocity_,filtered_wheel_velocity_);
00481
00482 double steer_angle_actual = 0;
00483 for(int i = 0; i < (int) base_kinematics_.num_wheels_; i++)
00484 {
00485 base_kinematics_.wheel_[i].updatePosition();
00486
00487 caster_2d_velocity.angular.z = base_kinematics_.wheel_[i].parent_->caster_position_error_;
00488 steer_angle_actual = base_kinematics_.wheel_[i].parent_->joint_->position_;
00489 wheel_point_velocity = base_kinematics_.pointVel2D(base_kinematics_.wheel_[i].position_, cmd_vel_);
00490 wheel_caster_steer_component = base_kinematics_.pointVel2D(base_kinematics_.wheel_[i].offset_, caster_2d_velocity);
00491
00492 double costh = cos(-steer_angle_actual);
00493 double sinth = sin(-steer_angle_actual);
00494
00495 wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
00496 wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;
00497 base_kinematics_.wheel_[i].wheel_speed_cmd_ = (wheel_point_velocity_projected.linear.x) / (base_kinematics_.wheel_[i].wheel_radius_);
00498 double command = wheel_pid_controllers_[i].updatePid(wheel_caster_steer_component.linear.x/base_kinematics_.wheel_[i].wheel_radius_,filtered_wheel_velocity_[i]-base_kinematics_.wheel_[i].wheel_speed_cmd_,ros::Duration(dT));
00499 base_kinematics_.wheel_[i].joint_->commanded_effort_ = command;
00500 }
00501 }
00502
00503 void Pr2BaseController2Safe::setDesiredWheelSpeeds()
00504 {
00505
00506
00507
00508
00509 }
00510
00511 void Pr2BaseController2Safe::updateJointControllers()
00512 {
00513
00514
00515
00516
00517 }
00518
00519 void Pr2BaseController2Safe::cmdLimitsCB(const safe_base_controller::TwistLimits &cmd_limits)
00520 {
00521 pthread_mutex_lock(&pr2_base_controller_lock_);
00522
00523 this->safe_max_x_ = std::max(cmd_limits.linear.x_max, 0.0);
00524 this->safe_min_x_ = std::min(cmd_limits.linear.x_min, 0.0);
00525 this->safe_max_y_ = std::max(cmd_limits.linear.y_max, 0.0);
00526 this->safe_min_y_ = std::min(cmd_limits.linear.y_min, 0.0);
00527 this->safe_max_z_ = std::max(cmd_limits.angular.z_max, 0.0);
00528 this->safe_min_z_ = std::min(cmd_limits.angular.z_min, 0.0);
00529 cmd_limits_timestamp_ = base_kinematics_.robot_state_->getTime();
00530 pthread_mutex_unlock(&pr2_base_controller_lock_);
00531 ROS_INFO("%f, %f | %f, %f | %f, %f | %f", safe_max_x_, safe_min_x_, safe_max_y_, safe_min_y_, safe_max_z_, safe_min_z_, cmd_limits_timestamp_.toSec());
00532 }
00533
00534 void Pr2BaseController2Safe::commandCallback(const geometry_msgs::TwistConstPtr& msg)
00535 {
00536 pthread_mutex_lock(&pr2_base_controller_lock_);
00537 base_vel_msg_ = *msg;
00538 this->setCommand(base_vel_msg_);
00539 pthread_mutex_unlock(&pr2_base_controller_lock_);
00540 }
00541 }