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 #include <cmath>
00040
00041 #include <tf/transform_datatypes.h>
00042
00043 #include <urdf_parser/urdf_parser.h>
00044
00045 #include <boost/assign.hpp>
00046
00047 #include <diff_drive_controller/diff_drive_controller.h>
00048
00049 static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& vec2)
00050 {
00051 return std::sqrt(std::pow(vec1.x-vec2.x,2) +
00052 std::pow(vec1.y-vec2.y,2) +
00053 std::pow(vec1.z-vec2.z,2));
00054 }
00055
00056
00057
00058
00059
00060
00061 static bool isCylinder(const boost::shared_ptr<const urdf::Link>& link)
00062 {
00063 if (!link)
00064 {
00065 ROS_ERROR("Link == NULL.");
00066 return false;
00067 }
00068
00069 if (!link->collision)
00070 {
00071 ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf.");
00072 return false;
00073 }
00074
00075 if (!link->collision->geometry)
00076 {
00077 ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf.");
00078 return false;
00079 }
00080
00081 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
00082 {
00083 ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder geometry");
00084 return false;
00085 }
00086
00087 return true;
00088 }
00089
00090
00091
00092
00093
00094
00095
00096 static bool getWheelRadius(const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius)
00097 {
00098 if (!isCylinder(wheel_link))
00099 {
00100 ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!");
00101 return false;
00102 }
00103
00104 wheel_radius = (static_cast<urdf::Cylinder*>(wheel_link->collision->geometry.get()))->radius;
00105 return true;
00106 }
00107
00108 namespace diff_drive_controller{
00109
00110 DiffDriveController::DiffDriveController()
00111 : open_loop_(false)
00112 , command_struct_()
00113 , wheel_separation_(0.0)
00114 , wheel_radius_(0.0)
00115 , wheel_separation_multiplier_(1.0)
00116 , wheel_radius_multiplier_(1.0)
00117 , cmd_vel_timeout_(0.5)
00118 , base_frame_id_("base_link")
00119 , enable_odom_tf_(true)
00120 , wheel_joints_size_(0)
00121 {
00122 }
00123
00124 bool DiffDriveController::init(hardware_interface::VelocityJointInterface* hw,
00125 ros::NodeHandle& root_nh,
00126 ros::NodeHandle &controller_nh)
00127 {
00128 const std::string complete_ns = controller_nh.getNamespace();
00129 std::size_t id = complete_ns.find_last_of("/");
00130 name_ = complete_ns.substr(id + 1);
00131
00132
00133 std::vector<std::string> left_wheel_names, right_wheel_names;
00134 if (!getWheelNames(controller_nh, "left_wheel", left_wheel_names) or
00135 !getWheelNames(controller_nh, "right_wheel", right_wheel_names))
00136 {
00137 return false;
00138 }
00139
00140 if (left_wheel_names.size() != right_wheel_names.size())
00141 {
00142 ROS_ERROR_STREAM_NAMED(name_,
00143 "#left wheels (" << left_wheel_names.size() << ") != " <<
00144 "#right wheels (" << right_wheel_names.size() << ").");
00145 return false;
00146 }
00147 else
00148 {
00149 wheel_joints_size_ = left_wheel_names.size();
00150
00151 left_wheel_joints_.resize(wheel_joints_size_);
00152 right_wheel_joints_.resize(wheel_joints_size_);
00153 }
00154
00155
00156 double publish_rate;
00157 controller_nh.param("publish_rate", publish_rate, 50.0);
00158 ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
00159 << publish_rate << "Hz.");
00160 publish_period_ = ros::Duration(1.0 / publish_rate);
00161
00162 controller_nh.param("open_loop", open_loop_, open_loop_);
00163
00164 controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_);
00165 ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by "
00166 << wheel_separation_multiplier_ << ".");
00167
00168 controller_nh.param("wheel_radius_multiplier", wheel_radius_multiplier_, wheel_radius_multiplier_);
00169 ROS_INFO_STREAM_NAMED(name_, "Wheel radius will be multiplied by "
00170 << wheel_radius_multiplier_ << ".");
00171
00172 int velocity_rolling_window_size = 10;
00173 controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
00174 ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
00175 << velocity_rolling_window_size << ".");
00176
00177 odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
00178
00179
00180 controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
00181 ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
00182 << cmd_vel_timeout_ << "s.");
00183
00184 controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
00185 ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
00186
00187 controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
00188 ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
00189
00190
00191 controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits );
00192 controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
00193 controller_nh.param("linear/x/has_jerk_limits" , limiter_lin_.has_jerk_limits , limiter_lin_.has_jerk_limits );
00194 controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity );
00195 controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity );
00196 controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration );
00197 controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration );
00198 controller_nh.param("linear/x/max_jerk" , limiter_lin_.max_jerk , limiter_lin_.max_jerk );
00199 controller_nh.param("linear/x/min_jerk" , limiter_lin_.min_jerk , -limiter_lin_.max_jerk );
00200
00201 controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits );
00202 controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
00203 controller_nh.param("angular/z/has_jerk_limits" , limiter_ang_.has_jerk_limits , limiter_ang_.has_jerk_limits );
00204 controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity );
00205 controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity );
00206 controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration );
00207 controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration );
00208 controller_nh.param("angular/z/max_jerk" , limiter_ang_.max_jerk , limiter_ang_.max_jerk );
00209 controller_nh.param("angular/z/min_jerk" , limiter_ang_.min_jerk , -limiter_ang_.max_jerk );
00210
00211
00212 bool lookup_wheel_separation = !controller_nh.getParam("wheel_separation", wheel_separation_);
00213 bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
00214
00215 if (!setOdomParamsFromUrdf(root_nh,
00216 left_wheel_names[0],
00217 right_wheel_names[0],
00218 lookup_wheel_separation,
00219 lookup_wheel_radius))
00220 {
00221 return false;
00222 }
00223
00224
00225
00226 const double ws = wheel_separation_multiplier_ * wheel_separation_;
00227 const double wr = wheel_radius_multiplier_ * wheel_radius_;
00228 odometry_.setWheelParams(ws, wr);
00229 ROS_INFO_STREAM_NAMED(name_,
00230 "Odometry params : wheel separation " << ws
00231 << ", wheel radius " << wr);
00232
00233 setOdomPubFields(root_nh, controller_nh);
00234
00235
00236 for (int i = 0; i < wheel_joints_size_; ++i)
00237 {
00238 ROS_INFO_STREAM_NAMED(name_,
00239 "Adding left wheel with joint name: " << left_wheel_names[i]
00240 << " and right wheel with joint name: " << right_wheel_names[i]);
00241 left_wheel_joints_[i] = hw->getHandle(left_wheel_names[i]);
00242 right_wheel_joints_[i] = hw->getHandle(right_wheel_names[i]);
00243 }
00244
00245 sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
00246
00247 return true;
00248 }
00249
00250 void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
00251 {
00252
00253 if (open_loop_)
00254 {
00255 odometry_.updateOpenLoop(last0_cmd_.lin, last0_cmd_.ang, time);
00256 }
00257 else
00258 {
00259 double left_pos = 0.0;
00260 double right_pos = 0.0;
00261 for (size_t i = 0; i < wheel_joints_size_; ++i)
00262 {
00263 const double lp = left_wheel_joints_[i].getPosition();
00264 const double rp = right_wheel_joints_[i].getPosition();
00265 if (std::isnan(lp) || std::isnan(rp))
00266 return;
00267
00268 left_pos += lp;
00269 right_pos += rp;
00270 }
00271 left_pos /= wheel_joints_size_;
00272 right_pos /= wheel_joints_size_;
00273
00274
00275 odometry_.update(left_pos, right_pos, time);
00276 }
00277
00278
00279 if (last_state_publish_time_ + publish_period_ < time)
00280 {
00281 last_state_publish_time_ += publish_period_;
00282
00283 const geometry_msgs::Quaternion orientation(
00284 tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
00285
00286
00287 if (odom_pub_->trylock())
00288 {
00289 odom_pub_->msg_.header.stamp = time;
00290 odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
00291 odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
00292 odom_pub_->msg_.pose.pose.orientation = orientation;
00293 odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinear();
00294 odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
00295 odom_pub_->unlockAndPublish();
00296 }
00297
00298
00299 if (enable_odom_tf_ && tf_odom_pub_->trylock())
00300 {
00301 geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
00302 odom_frame.header.stamp = time;
00303 odom_frame.transform.translation.x = odometry_.getX();
00304 odom_frame.transform.translation.y = odometry_.getY();
00305 odom_frame.transform.rotation = orientation;
00306 tf_odom_pub_->unlockAndPublish();
00307 }
00308 }
00309
00310
00311
00312 Commands curr_cmd = *(command_.readFromRT());
00313 const double dt = (time - curr_cmd.stamp).toSec();
00314
00315
00316 if (dt > cmd_vel_timeout_)
00317 {
00318 curr_cmd.lin = 0.0;
00319 curr_cmd.ang = 0.0;
00320 }
00321
00322
00323 const double cmd_dt(period.toSec());
00324
00325 limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt);
00326 limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
00327
00328 last1_cmd_ = last0_cmd_;
00329 last0_cmd_ = curr_cmd;
00330
00331
00332 const double ws = wheel_separation_multiplier_ * wheel_separation_;
00333 const double wr = wheel_radius_multiplier_ * wheel_radius_;
00334
00335
00336 const double vel_left = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wr;
00337 const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wr;
00338
00339
00340 for (size_t i = 0; i < wheel_joints_size_; ++i)
00341 {
00342 left_wheel_joints_[i].setCommand(vel_left);
00343 right_wheel_joints_[i].setCommand(vel_right);
00344 }
00345 }
00346
00347 void DiffDriveController::starting(const ros::Time& time)
00348 {
00349 brake();
00350
00351
00352 last_state_publish_time_ = time;
00353
00354 odometry_.init(time);
00355 }
00356
00357 void DiffDriveController::stopping(const ros::Time& )
00358 {
00359 brake();
00360 }
00361
00362 void DiffDriveController::brake()
00363 {
00364 const double vel = 0.0;
00365 for (size_t i = 0; i < wheel_joints_size_; ++i)
00366 {
00367 left_wheel_joints_[i].setCommand(vel);
00368 right_wheel_joints_[i].setCommand(vel);
00369 }
00370 }
00371
00372 void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
00373 {
00374 if (isRunning())
00375 {
00376 command_struct_.ang = command.angular.z;
00377 command_struct_.lin = command.linear.x;
00378 command_struct_.stamp = ros::Time::now();
00379 command_.writeFromNonRT (command_struct_);
00380 ROS_DEBUG_STREAM_NAMED(name_,
00381 "Added values to command. "
00382 << "Ang: " << command_struct_.ang << ", "
00383 << "Lin: " << command_struct_.lin << ", "
00384 << "Stamp: " << command_struct_.stamp);
00385 }
00386 else
00387 {
00388 ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
00389 }
00390 }
00391
00392 bool DiffDriveController::getWheelNames(ros::NodeHandle& controller_nh,
00393 const std::string& wheel_param,
00394 std::vector<std::string>& wheel_names)
00395 {
00396 XmlRpc::XmlRpcValue wheel_list;
00397 if (!controller_nh.getParam(wheel_param, wheel_list))
00398 {
00399 ROS_ERROR_STREAM_NAMED(name_,
00400 "Couldn't retrieve wheel param '" << wheel_param << "'.");
00401 return false;
00402 }
00403
00404 if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
00405 {
00406 if (wheel_list.size() == 0)
00407 {
00408 ROS_ERROR_STREAM_NAMED(name_,
00409 "Wheel param '" << wheel_param << "' is an empty list");
00410 return false;
00411 }
00412
00413 for (int i = 0; i < wheel_list.size(); ++i)
00414 {
00415 if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
00416 {
00417 ROS_ERROR_STREAM_NAMED(name_,
00418 "Wheel param '" << wheel_param << "' #" << i <<
00419 " isn't a string.");
00420 return false;
00421 }
00422 }
00423
00424 wheel_names.resize(wheel_list.size());
00425 for (int i = 0; i < wheel_list.size(); ++i)
00426 {
00427 wheel_names[i] = static_cast<std::string>(wheel_list[i]);
00428 }
00429 }
00430 else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
00431 {
00432 wheel_names.push_back(wheel_list);
00433 }
00434 else
00435 {
00436 ROS_ERROR_STREAM_NAMED(name_,
00437 "Wheel param '" << wheel_param <<
00438 "' is neither a list of strings nor a string.");
00439 return false;
00440 }
00441
00442 return true;
00443 }
00444
00445 bool DiffDriveController::setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00446 const std::string& left_wheel_name,
00447 const std::string& right_wheel_name,
00448 bool lookup_wheel_separation,
00449 bool lookup_wheel_radius)
00450 {
00451 if (!(lookup_wheel_separation || lookup_wheel_radius))
00452 {
00453
00454 return true;
00455 }
00456
00457
00458 const std::string model_param_name = "robot_description";
00459 bool res = root_nh.hasParam(model_param_name);
00460 std::string robot_model_str="";
00461 if (!res || !root_nh.getParam(model_param_name,robot_model_str))
00462 {
00463 ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
00464 return false;
00465 }
00466
00467 boost::shared_ptr<urdf::ModelInterface> model(urdf::parseURDF(robot_model_str));
00468
00469 boost::shared_ptr<const urdf::Joint> left_wheel_joint(model->getJoint(left_wheel_name));
00470 boost::shared_ptr<const urdf::Joint> right_wheel_joint(model->getJoint(right_wheel_name));
00471
00472 if (lookup_wheel_separation)
00473 {
00474
00475 if (!left_wheel_joint)
00476 {
00477 ROS_ERROR_STREAM_NAMED(name_, left_wheel_name
00478 << " couldn't be retrieved from model description");
00479 return false;
00480 }
00481
00482 if (!right_wheel_joint)
00483 {
00484 ROS_ERROR_STREAM_NAMED(name_, right_wheel_name
00485 << " couldn't be retrieved from model description");
00486 return false;
00487 }
00488
00489 ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00490 << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00491 << left_wheel_joint->parent_to_joint_origin_transform.position.z);
00492 ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << ","
00493 << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
00494 << right_wheel_joint->parent_to_joint_origin_transform.position.z);
00495
00496 wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position,
00497 right_wheel_joint->parent_to_joint_origin_transform.position);
00498
00499 }
00500
00501 if (lookup_wheel_radius)
00502 {
00503
00504 if (!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_))
00505 {
00506 ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius");
00507 return false;
00508 }
00509 }
00510
00511 return true;
00512 }
00513
00514 void DiffDriveController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
00515 {
00516
00517 XmlRpc::XmlRpcValue pose_cov_list;
00518 controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
00519 ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00520 ROS_ASSERT(pose_cov_list.size() == 6);
00521 for (int i = 0; i < pose_cov_list.size(); ++i)
00522 ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00523
00524 XmlRpc::XmlRpcValue twist_cov_list;
00525 controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
00526 ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00527 ROS_ASSERT(twist_cov_list.size() == 6);
00528 for (int i = 0; i < twist_cov_list.size(); ++i)
00529 ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
00530
00531
00532 odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
00533 odom_pub_->msg_.header.frame_id = "odom";
00534 odom_pub_->msg_.child_frame_id = base_frame_id_;
00535 odom_pub_->msg_.pose.pose.position.z = 0;
00536 odom_pub_->msg_.pose.covariance = boost::assign::list_of
00537 (static_cast<double>(pose_cov_list[0])) (0) (0) (0) (0) (0)
00538 (0) (static_cast<double>(pose_cov_list[1])) (0) (0) (0) (0)
00539 (0) (0) (static_cast<double>(pose_cov_list[2])) (0) (0) (0)
00540 (0) (0) (0) (static_cast<double>(pose_cov_list[3])) (0) (0)
00541 (0) (0) (0) (0) (static_cast<double>(pose_cov_list[4])) (0)
00542 (0) (0) (0) (0) (0) (static_cast<double>(pose_cov_list[5]));
00543 odom_pub_->msg_.twist.twist.linear.y = 0;
00544 odom_pub_->msg_.twist.twist.linear.z = 0;
00545 odom_pub_->msg_.twist.twist.angular.x = 0;
00546 odom_pub_->msg_.twist.twist.angular.y = 0;
00547 odom_pub_->msg_.twist.covariance = boost::assign::list_of
00548 (static_cast<double>(twist_cov_list[0])) (0) (0) (0) (0) (0)
00549 (0) (static_cast<double>(twist_cov_list[1])) (0) (0) (0) (0)
00550 (0) (0) (static_cast<double>(twist_cov_list[2])) (0) (0) (0)
00551 (0) (0) (0) (static_cast<double>(twist_cov_list[3])) (0) (0)
00552 (0) (0) (0) (0) (static_cast<double>(twist_cov_list[4])) (0)
00553 (0) (0) (0) (0) (0) (static_cast<double>(twist_cov_list[5]));
00554 tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
00555 tf_odom_pub_->msg_.transforms.resize(1);
00556 tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
00557 tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
00558 tf_odom_pub_->msg_.transforms[0].header.frame_id = "odom";
00559 }
00560
00561 }