45 const static double EPS = 1e-5;
47 Pr2BaseController::Pr2BaseController()
50 cmd_vel_.linear.x = 0;
51 cmd_vel_.linear.y = 0;
52 cmd_vel_.angular.z = 0;
54 desired_vel_.linear.x = 0;
55 desired_vel_.linear.y = 0;
56 desired_vel_.angular.z = 0;
58 cmd_vel_t_.linear.x = 0;
59 cmd_vel_t_.linear.y = 0;
60 cmd_vel_t_.angular.z = 0;
62 new_cmd_available_ =
false;
65 pthread_mutex_init(&pr2_base_controller_lock_, NULL);
68 Pr2BaseController::~Pr2BaseController()
71 cmd_sub_deprecated_.shutdown();
76 if(!base_kin_.init(robot,n))
81 int num_joints = base_kin_.num_wheels_ + base_kin_.num_casters_;
82 state_publisher_->msg_.joint_names.resize(num_joints);
83 state_publisher_->msg_.joint_velocity_measured.resize(num_joints);
84 state_publisher_->msg_.joint_effort_measured.resize(num_joints);
85 state_publisher_->msg_.joint_velocity_commanded.resize(num_joints);
86 state_publisher_->msg_.joint_effort_commanded.resize(num_joints);
87 state_publisher_->msg_.joint_velocity_error.resize(num_joints);
88 state_publisher_->msg_.joint_effort_error.resize(num_joints);
91 node_.
param<
double> (
"max_translational_velocity", max_translational_velocity_,0.5);
92 node_.param<
double> (
"max_rotational_velocity", max_rotational_velocity_, 10.0);
93 node_.param<
double> (
"max_translational_acceleration/x", max_accel_.linear.x, .2);
94 node_.param<
double> (
"max_translational_acceleration/y", max_accel_.linear.y, .2);
95 node_.param<
double> (
"max_rotational_acceleration", max_accel_.angular.z, 10.0);
97 node_.param<
double> (
"kp_caster_steer", kp_caster_steer_, 80.0);
98 node_.param<
double> (
"timeout", timeout_, 1.0);
99 node_.param<
double> (
"state_publish_rate", state_publish_rate_,2.0);
100 if(state_publish_rate_ <= 0.0)
102 publish_state_ =
false;
103 state_publish_time_ = 0.0;
107 publish_state_ =
true;
108 state_publish_time_ = 1.0/state_publish_rate_;
112 cmd_sub_ = node_.subscribe<geometry_msgs::Twist>(
"command", 1, &Pr2BaseController::commandCallback,
this);
115 caster_controller_.resize(base_kin_.num_casters_);
116 caster_position_pid_.resize(base_kin_.num_casters_);
117 for(
int i = 0; i < base_kin_.num_casters_; i++)
120 state_publisher_->msg_.joint_names[i] = base_kin_.caster_[i].joint_name_;
121 if(!p_i_d.
init(
ros::NodeHandle(node_, base_kin_.caster_[i].joint_name_+
"/velocity_controller")))
123 ROS_ERROR(
"Could not initialize pid for %s",base_kin_.caster_[i].joint_name_.c_str());
127 if(!caster_position_pid_[i].init(
ros::NodeHandle(node_, base_kin_.caster_[i].joint_name_+
"/position_controller")))
129 ROS_ERROR(
"Could not initialize position pid controller for %s",base_kin_.caster_[i].joint_name_.c_str());
133 if(!caster_controller_[i]->init(base_kin_.robot_state_, base_kin_.caster_[i].joint_name_, p_i_d))
135 ROS_ERROR(
"Could not initialize pid for %s",base_kin_.caster_[i].joint_name_.c_str());
138 if (!caster_controller_[i]->joint_state_->calibrated_)
140 ROS_ERROR(
"Caster joint \"%s\" not calibrated (namespace: %s)",
141 base_kin_.caster_[i].joint_name_.c_str(), node_.getNamespace().c_str());
146 wheel_controller_.resize(base_kin_.num_wheels_);
147 for(
int j = 0; j < base_kin_.num_wheels_; j++)
150 state_publisher_->msg_.joint_names[j + base_kin_.num_casters_] = base_kin_.wheel_[j].joint_name_;
153 ROS_ERROR(
"Could not initialize pid for %s",base_kin_.wheel_[j].joint_name_.c_str());
157 if(!wheel_controller_[j]->init(base_kin_.robot_state_, base_kin_.wheel_[j].joint_name_, p_i_d))
159 ROS_ERROR(
"Could not initialize joint velocity controller for %s",base_kin_.wheel_[j].joint_name_.c_str());
163 for(
int i = 0; i < base_kin_.num_casters_; ++i)
165 if(!base_kin_.caster_[i].joint_->calibrated_)
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");
176 filtered_velocity_.resize(base_kin_.num_casters_);
181 void Pr2BaseController::setCommand(
const geometry_msgs::Twist &cmd_vel)
183 double vel_mag =
sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
184 double clamped_vel_mag =
filters::clamp(vel_mag,-max_translational_velocity_, max_translational_velocity_);
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;
192 cmd_vel_t_.linear.x = 0.0;
193 cmd_vel_t_.linear.y = 0.0;
195 cmd_vel_t_.angular.z =
filters::clamp(cmd_vel.angular.z, -max_rotational_velocity_, max_rotational_velocity_);
196 cmd_received_timestamp_ = base_kin_.robot_state_->getTime();
198 ROS_DEBUG(
"BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
199 ROS_DEBUG(
"BaseController:: command current: %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);
203 for(
int i=0; i < (int) base_kin_.num_wheels_; i++)
205 ROS_DEBUG(
"BaseController:: wheel speed cmd:: %d %f",i,(base_kin_.wheel_[i].direction_multiplier_*base_kin_.wheel_[i].wheel_speed_cmd_));
207 for(
int i=0; i < (int) base_kin_.num_casters_; i++)
209 ROS_DEBUG(
"BaseController:: caster speed cmd:: %d %f",i,(base_kin_.caster_[i].steer_velocity_desired_));
211 new_cmd_available_ =
true;
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);
253 geometry_msgs::Twist Pr2BaseController::getCommand()
255 geometry_msgs::Twist cmd_vel;
256 pthread_mutex_lock(&pr2_base_controller_lock_);
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;
260 pthread_mutex_unlock(&pr2_base_controller_lock_);
264 void Pr2BaseController::starting()
266 last_time_ = base_kin_.robot_state_->getTime();
267 cmd_received_timestamp_ = base_kin_.robot_state_->getTime();
268 for(
int i = 0; i < base_kin_.num_casters_; i++)
270 caster_controller_[i]->starting();
272 for(
int j = 0; j < base_kin_.num_wheels_; j++)
274 wheel_controller_[j]->starting();
278 void Pr2BaseController::update()
280 ros::Time current_time = base_kin_.robot_state_->getTime();
281 double dT = std::min<double>((current_time - last_time_).toSec(), base_kin_.MAX_DT_);
283 if(new_cmd_available_)
285 if(pthread_mutex_trylock(&pr2_base_controller_lock_) == 0)
287 desired_vel_.linear.x = cmd_vel_t_.linear.x;
288 desired_vel_.linear.y = cmd_vel_t_.linear.y;
289 desired_vel_.angular.z = cmd_vel_t_.angular.z;
290 new_cmd_available_ =
false;
291 pthread_mutex_unlock(&pr2_base_controller_lock_);
295 if((current_time - cmd_received_timestamp_).toSec() > timeout_)
297 cmd_vel_.linear.x = 0;
298 cmd_vel_.linear.y = 0;
299 cmd_vel_.angular.z = 0;
302 cmd_vel_ = interpolateCommand(cmd_vel_, desired_vel_, max_accel_, dT);
304 computeJointCommands(dT);
308 updateJointControllers();
311 publishState(current_time);
313 last_time_ = current_time;
317 void Pr2BaseController::publishState(
const ros::Time &time)
319 if((time - last_publish_time_).toSec() < state_publish_time_)
324 if(state_publisher_->trylock())
326 state_publisher_->msg_.command.linear.x = cmd_vel_.linear.x;
327 state_publisher_->msg_.command.linear.y = cmd_vel_.linear.y;
328 state_publisher_->msg_.command.angular.z = cmd_vel_.angular.z;
330 for(
int i = 0; i < base_kin_.num_casters_; i++)
332 state_publisher_->msg_.joint_names[i] = base_kin_.caster_[i].joint_name_;
333 state_publisher_->msg_.joint_velocity_measured[i] = base_kin_.caster_[i].joint_->velocity_;
334 state_publisher_->msg_.joint_velocity_commanded[i]= base_kin_.caster_[i].steer_velocity_desired_;
335 state_publisher_->msg_.joint_velocity_error[i] = base_kin_.caster_[i].joint_->velocity_ - base_kin_.caster_[i].steer_velocity_desired_;
337 state_publisher_->msg_.joint_effort_measured[i] = base_kin_.caster_[i].joint_->measured_effort_;
338 state_publisher_->msg_.joint_effort_commanded[i] = base_kin_.caster_[i].joint_->commanded_effort_;
339 state_publisher_->msg_.joint_effort_error[i] = base_kin_.caster_[i].joint_->measured_effort_ - base_kin_.caster_[i].joint_->commanded_effort_;
341 for(
int i = 0; i < base_kin_.num_wheels_; i++)
343 state_publisher_->msg_.joint_names[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_name_;
344 state_publisher_->msg_.joint_velocity_measured[i+base_kin_.num_casters_] = base_kin_.wheel_[i].wheel_speed_actual_;
345 state_publisher_->msg_.joint_velocity_commanded[i+base_kin_.num_casters_]= base_kin_.wheel_[i].wheel_speed_error_;
346 state_publisher_->msg_.joint_velocity_error[i+base_kin_.num_casters_] = base_kin_.wheel_[i].wheel_speed_cmd_;
348 state_publisher_->msg_.joint_effort_measured[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->measured_effort_;
349 state_publisher_->msg_.joint_effort_commanded[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->commanded_effort_;
350 state_publisher_->msg_.joint_effort_error[i+base_kin_.num_casters_] = base_kin_.wheel_[i].joint_->measured_effort_ - base_kin_.wheel_[i].joint_->commanded_effort_;
352 state_publisher_->unlockAndPublish();
353 last_publish_time_ = time;
357 void Pr2BaseController::computeJointCommands(
const double &dT)
359 base_kin_.computeWheelPositions();
361 computeDesiredCasterSteer(dT);
363 computeDesiredWheelSpeeds();
366 void Pr2BaseController::setJointCommands()
368 setDesiredCasterSteer();
370 setDesiredWheelSpeeds();
373 void Pr2BaseController::computeDesiredCasterSteer(
const double &dT)
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);
379 double trans_vel =
sqrt(cmd_vel_.linear.x * cmd_vel_.linear.x + cmd_vel_.linear.y * cmd_vel_.linear.y);
381 for(
int i = 0; i < base_kin_.num_casters_; i++)
383 filtered_velocity_[i] = 0.0 - base_kin_.caster_[i].joint_->velocity_;
385 caster_vel_filter_.update(filtered_velocity_,filtered_velocity_);
387 for(
int i = 0; i < base_kin_.num_casters_; i++)
389 result = base_kin_.pointVel2D(base_kin_.caster_[i].offset_, cmd_vel_);
390 if(trans_vel < EPS && fabs(cmd_vel_.angular.z) < EPS)
392 steer_angle_desired = base_kin_.caster_[i].steer_angle_stored_;
396 steer_angle_desired =
atan2(result.linear.y, result.linear.x);
397 base_kin_.caster_[i].steer_angle_stored_ = steer_angle_desired;
401 base_kin_.caster_[i].joint_->position_,
402 steer_angle_desired);
404 base_kin_.caster_[i].joint_->position_,
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;
413 base_kin_.caster_[i].steer_velocity_desired_ = caster_position_pid_[i].computeCommand(
415 filtered_velocity_[i],
417 base_kin_.caster_[i].caster_position_error_ = error_steer;
421 void Pr2BaseController::setDesiredCasterSteer()
423 for(
int i = 0; i < base_kin_.num_casters_; i++)
425 caster_controller_[i]->setCommand(base_kin_.caster_[i].steer_velocity_desired_);
429 void Pr2BaseController::computeDesiredWheelSpeeds()
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;
441 for(
int i = 0; i < (int) base_kin_.num_wheels_; i++)
443 base_kin_.wheel_[i].updatePosition();
444 caster_2d_velocity.angular.z = base_kin_.wheel_[i].parent_->steer_velocity_desired_;
445 steer_angle_actual = base_kin_.wheel_[i].parent_->joint_->position_;
446 wheel_point_velocity = base_kin_.pointVel2D(base_kin_.wheel_[i].position_, cmd_vel_);
447 wheel_caster_steer_component = base_kin_.pointVel2D(base_kin_.wheel_[i].offset_, caster_2d_velocity);
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_);
458 void Pr2BaseController::setDesiredWheelSpeeds()
460 for(
int i = 0; i < (int) base_kin_.num_wheels_; i++)
462 wheel_controller_[i]->setCommand(base_kin_.wheel_[i].direction_multiplier_ * base_kin_.wheel_[i].wheel_speed_cmd_);
466 void Pr2BaseController::updateJointControllers()
468 for(
int i = 0; i < base_kin_.num_wheels_; i++)
469 wheel_controller_[i]->
update();
470 for(
int i = 0; i < base_kin_.num_casters_; i++)
471 caster_controller_[i]->
update();
474 void Pr2BaseController::commandCallback(
const geometry_msgs::TwistConstPtr& msg)
476 pthread_mutex_lock(&pr2_base_controller_lock_);
477 base_vel_msg_ = *msg;
478 this->setCommand(base_vel_msg_);
479 pthread_mutex_unlock(&pr2_base_controller_lock_);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static const T & clamp(const T &a, const T &b, const T &c)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
def shortest_angular_distance(from_angle, to_angle)