00001
00002
00003
00004 #include <robotican_hardware_interface/armadillo2_sim_interface.h>
00005 namespace
00006 {
00007
00008 double clamp(const double val, const double min_val, const double max_val)
00009 {
00010 return std::min(std::max(val, min_val), max_val);
00011 }
00012
00013 }
00014
00015 namespace gazebo_ros_control
00016 {
00017
00018
00019 bool Armadillo2RobotHWSim::initSim(
00020 const std::string& robot_namespace,
00021 ros::NodeHandle model_nh,
00022 gazebo::physics::ModelPtr parent_model,
00023 const urdf::Model *const urdf_model,
00024 std::vector<transmission_interface::TransmissionInfo> transmissions)
00025 {
00026
00027
00028 const ros::NodeHandle joint_limit_nh(model_nh, robot_namespace);
00029
00030
00031 n_dof_ = transmissions.size();
00032 joint_names_.resize(n_dof_);
00033 joint_types_.resize(n_dof_);
00034 joint_lower_limits_.resize(n_dof_);
00035 joint_upper_limits_.resize(n_dof_);
00036 joint_effort_limits_.resize(n_dof_);
00037 joint_control_methods_.resize(n_dof_);
00038 pid_controllers_.resize(n_dof_);
00039 joint_position_.resize(n_dof_);
00040 joint_velocity_.resize(n_dof_);
00041 joint_effort_.resize(n_dof_);
00042 joint_effort_command_.resize(n_dof_);
00043 joint_position_command_.resize(n_dof_);
00044 joint_velocity_command_.resize(n_dof_);
00045
00046
00047 for(unsigned int j=0; j < n_dof_; j++)
00048 {
00049
00050 if(transmissions[j].joints_.size() == 0)
00051 {
00052 ROS_WARN_STREAM_NAMED("default_robot_hw_sim","Transmission " << transmissions[j].name_
00053 << " has no associated joints.");
00054 continue;
00055 }
00056 else if(transmissions[j].joints_.size() > 1)
00057 {
00058 ROS_WARN_STREAM_NAMED("default_robot_hw_sim","Transmission " << transmissions[j].name_
00059 << " has more than one joint. Currently the default robot hardware simulation "
00060 << " interface only supports one.");
00061 continue;
00062 }
00063
00064 std::vector<std::string> joint_interfaces = transmissions[j].joints_[0].hardware_interfaces_;
00065 if (joint_interfaces.empty() &&
00066 !(transmissions[j].actuators_.empty()) &&
00067 !(transmissions[j].actuators_[0].hardware_interfaces_.empty()))
00068 {
00069
00070 joint_interfaces = transmissions[j].actuators_[0].hardware_interfaces_;
00071 ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "The <hardware_interface> element of tranmission " <<
00072 transmissions[j].name_ << " should be nested inside the <joint> element, not <actuator>. " <<
00073 "The transmission will be properly loaded, but please update " <<
00074 "your robot model to remain compatible with future versions of the plugin.");
00075 }
00076 if (joint_interfaces.empty())
00077 {
00078 ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ <<
00079 " of transmission " << transmissions[j].name_ << " does not specify any hardware interface. " <<
00080 "Not adding it to the robot hardware simulation.");
00081 continue;
00082 }
00083 else if (joint_interfaces.size() > 1)
00084 {
00085 ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "Joint " << transmissions[j].joints_[0].name_ <<
00086 " of transmission " << transmissions[j].name_ << " specifies multiple hardware interfaces. " <<
00087 "Currently the default robot hardware simulation interface only supports one. Using the first entry!");
00088
00089 }
00090
00091
00092 joint_names_[j] = transmissions[j].joints_[0].name_;
00093 joint_position_[j] = 1.0;
00094 joint_velocity_[j] = 0.0;
00095 joint_effort_[j] = 1.0;
00096 joint_effort_command_[j] = 0.0;
00097 joint_position_command_[j] = 0.0;
00098 joint_velocity_command_[j] = 0.0;
00099
00100 const std::string& hardware_interface = joint_interfaces.front();
00101
00102
00103 ROS_DEBUG_STREAM_NAMED("default_robot_hw_sim","Loading joint '" << joint_names_[j]
00104 << "' of type '" << hardware_interface << "'");
00105
00106
00107 js_interface_.registerHandle(hardware_interface::JointStateHandle(
00108 joint_names_[j], &joint_position_[j], &joint_velocity_[j], &joint_effort_[j]));
00109
00110
00111 hardware_interface::JointHandle joint_handle;
00112 hardware_interface::PosVelJointHandle jointHandlePosVel;
00113 if(hardware_interface == "EffortJointInterface")
00114 {
00115
00116 joint_control_methods_[j] = EFFORT;
00117 joint_handle = hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[j]),
00118 &joint_effort_command_[j]);
00119 ej_interface_.registerHandle(joint_handle);
00120 }
00121 else if(hardware_interface == "PositionJointInterface")
00122 {
00123
00124 joint_control_methods_[j] = POSITION;
00125 joint_handle = hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[j]),
00126 &joint_position_command_[j]);
00127 pj_interface_.registerHandle(joint_handle);
00128 }
00129 else if(hardware_interface == "VelocityJointInterface")
00130 {
00131
00132 joint_control_methods_[j] = VELOCITY;
00133 joint_handle = hardware_interface::JointHandle(js_interface_.getHandle(joint_names_[j]),
00134 &joint_velocity_command_[j]);
00135 vj_interface_.registerHandle(joint_handle);
00136 }
00137 else if(hardware_interface == "PosVelJointInterface")
00138 {
00139
00140 joint_control_methods_[j] = POS_VEL;
00141
00142
00143
00144 jointHandlePosVel = hardware_interface::PosVelJointHandle(js_interface_.getHandle(joint_names_[j]), &joint_position_command_[j], &joint_velocity_command_[j]);
00145 pvj_interface_.registerHandle(jointHandlePosVel);
00146 }
00147 else
00148 {
00149 ROS_FATAL_STREAM_NAMED("default_robot_hw_sim","No matching hardware interface found for '"
00150 << hardware_interface );
00151 return false;
00152 }
00153
00154
00155
00156
00157 gazebo::physics::JointPtr joint = parent_model->GetJoint(joint_names_[j]);
00158 if (!joint)
00159 {
00160 ROS_ERROR_STREAM("This robot has a joint named \"" << joint_names_[j]
00161 << "\" which is not in the gazebo model.");
00162 return false;
00163 }
00164 sim_joints_.push_back(joint);
00165 if(!joint_control_methods_[j] != POS_VEL) {
00166 registerJointLimits(joint_names_[j], joint_handle, joint_control_methods_[j],
00167 joint_limit_nh, urdf_model,
00168 &joint_types_[j], &joint_lower_limits_[j], &joint_upper_limits_[j],
00169 &joint_effort_limits_[j]);
00170 }
00171 else {
00172 registerJointLimits(joint_names_[j], jointHandlePosVel, joint_control_methods_[j],
00173 joint_limit_nh, urdf_model,
00174 &joint_types_[j], &joint_lower_limits_[j], &joint_upper_limits_[j],
00175 &joint_effort_limits_[j]);
00176 }
00177
00178
00179 if (joint_control_methods_[j] != EFFORT)
00180 {
00181
00182
00183 const ros::NodeHandle nh(model_nh, robot_namespace + "/gazebo_ros_control/pid_gains/" +
00184 joint_names_[j]);
00185 if (pid_controllers_[j].init(nh, true))
00186 {
00187 switch (joint_control_methods_[j])
00188 {
00189 case POSITION:
00190 joint_control_methods_[j] = POSITION_PID;
00191 break;
00192 case VELOCITY:
00193 joint_control_methods_[j] = VELOCITY_PID;
00194 break;
00195 }
00196 }
00197 else
00198 {
00199
00200
00201
00202 joint->SetMaxForce(0, joint_effort_limits_[j]);
00203
00204 }
00205 }
00206 }
00207
00208
00209 registerInterface(&js_interface_);
00210 registerInterface(&ej_interface_);
00211 registerInterface(&pj_interface_);
00212 registerInterface(&vj_interface_);
00213 registerInterface(&pvj_interface_);
00214
00215
00216 e_stop_active_ = false;
00217 last_e_stop_active_ = false;
00218
00219 return true;
00220 }
00221
00222 void Armadillo2RobotHWSim::readSim(ros::Time time, ros::Duration period)
00223 {
00224 for(unsigned int j=0; j < n_dof_; j++)
00225 {
00226
00227 if (joint_types_[j] == urdf::Joint::PRISMATIC)
00228 {
00229 joint_position_[j] = sim_joints_[j]->GetAngle(0).Radian();
00230 }
00231 else
00232 {
00233 joint_position_[j] += angles::shortest_angular_distance(joint_position_[j],
00234 sim_joints_[j]->GetAngle(0).Radian());
00235 }
00236 joint_velocity_[j] = sim_joints_[j]->GetVelocity(0);
00237 joint_effort_[j] = sim_joints_[j]->GetForce((unsigned int)(0));
00238 }
00239 }
00240
00241 void Armadillo2RobotHWSim::writeSim(ros::Time time, ros::Duration period)
00242 {
00243
00244 if (e_stop_active_)
00245 {
00246 if (!last_e_stop_active_)
00247 {
00248 last_joint_position_command_ = joint_position_;
00249 last_e_stop_active_ = true;
00250 }
00251 joint_position_command_ = last_joint_position_command_;
00252 }
00253 else
00254 {
00255 last_e_stop_active_ = false;
00256 }
00257
00258 ej_sat_interface_.enforceLimits(period);
00259 ej_limits_interface_.enforceLimits(period);
00260 pj_sat_interface_.enforceLimits(period);
00261 pj_limits_interface_.enforceLimits(period);
00262 vj_sat_interface_.enforceLimits(period);
00263 vj_limits_interface_.enforceLimits(period);
00264
00265 for(unsigned int j=0; j < n_dof_; j++)
00266 {
00267 switch (joint_control_methods_[j])
00268 {
00269
00270 case POS_VEL:
00271 #if GAZEBO_MAJOR_VERSION >= 4
00272 sim_joints_[j]->SetPosition(0, joint_position_command_[j]);
00273 #else
00274 sim_joints_[j]->SetAngle(0, joint_position_command_[j]);
00275 #endif
00276 sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_command_[j]);
00277 break;
00278
00279 case EFFORT:
00280 {
00281 const double effort = e_stop_active_ ? 0 : joint_effort_command_[j];
00282 sim_joints_[j]->SetForce(0, effort);
00283 }
00284 break;
00285
00286 case POSITION:
00287 #if GAZEBO_MAJOR_VERSION >= 4
00288 sim_joints_[j]->SetPosition(0, joint_position_command_[j]);
00289 #else
00290 sim_joints_[j]->SetAngle(0, joint_position_command_[j]);
00291 #endif
00292 break;
00293
00294 case POSITION_PID:
00295 {
00296 double error;
00297 switch (joint_types_[j])
00298 {
00299 case urdf::Joint::REVOLUTE:
00300 angles::shortest_angular_distance_with_limits(joint_position_[j],
00301 joint_position_command_[j],
00302 joint_lower_limits_[j],
00303 joint_upper_limits_[j],
00304 error);
00305 break;
00306 case urdf::Joint::CONTINUOUS:
00307 error = angles::shortest_angular_distance(joint_position_[j],
00308 joint_position_command_[j]);
00309 break;
00310 default:
00311 error = joint_position_command_[j] - joint_position_[j];
00312 }
00313
00314 const double effort_limit = joint_effort_limits_[j];
00315 const double effort = clamp(pid_controllers_[j].computeCommand(error, period),
00316 -effort_limit, effort_limit);
00317 sim_joints_[j]->SetForce(0, effort);
00318 }
00319 break;
00320
00321 case VELOCITY:
00322 sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_command_[j]);
00323 break;
00324
00325 case VELOCITY_PID:
00326 double error;
00327 if (e_stop_active_)
00328 error = -joint_velocity_[j];
00329 else
00330 error = joint_velocity_command_[j] - joint_velocity_[j];
00331 const double effort_limit = joint_effort_limits_[j];
00332 const double effort = clamp(pid_controllers_[j].computeCommand(error, period),
00333 -effort_limit, effort_limit);
00334 sim_joints_[j]->SetForce(0, effort);
00335 break;
00336
00337 }
00338 }
00339 }
00340
00341 void Armadillo2RobotHWSim::eStopActive(const bool active)
00342 {
00343 e_stop_active_ = active;
00344 }
00345
00346
00347
00348
00349 void Armadillo2RobotHWSim::registerJointLimits(const std::string& joint_name,
00350 const hardware_interface::JointHandle& joint_handle,
00351 const ControlMethod ctrl_method,
00352 const ros::NodeHandle& joint_limit_nh,
00353 const urdf::Model *const urdf_model,
00354 int *const joint_type, double *const lower_limit,
00355 double *const upper_limit, double *const effort_limit)
00356 {
00357 *joint_type = urdf::Joint::UNKNOWN;
00358 *lower_limit = -std::numeric_limits<double>::max();
00359 *upper_limit = std::numeric_limits<double>::max();
00360 *effort_limit = std::numeric_limits<double>::max();
00361
00362 joint_limits_interface::JointLimits limits;
00363 bool has_limits = false;
00364 joint_limits_interface::SoftJointLimits soft_limits;
00365 bool has_soft_limits = false;
00366
00367 if (urdf_model != NULL)
00368 {
00369 const boost::shared_ptr<const urdf::Joint> urdf_joint = urdf_model->getJoint(joint_name);
00370 if (urdf_joint != NULL)
00371 {
00372 *joint_type = urdf_joint->type;
00373
00374 if (joint_limits_interface::getJointLimits(urdf_joint, limits))
00375 has_limits = true;
00376 if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits))
00377 has_soft_limits = true;
00378 }
00379 }
00380
00381 if (joint_limits_interface::getJointLimits(joint_name, joint_limit_nh, limits))
00382 has_limits = true;
00383
00384 if (!has_limits)
00385 return;
00386
00387 if (*joint_type == urdf::Joint::UNKNOWN)
00388 {
00389
00390
00391 if (limits.has_position_limits)
00392 {
00393 *joint_type = urdf::Joint::REVOLUTE;
00394 }
00395 else
00396 {
00397 if (limits.angle_wraparound)
00398 *joint_type = urdf::Joint::CONTINUOUS;
00399 else
00400 *joint_type = urdf::Joint::PRISMATIC;
00401 }
00402 }
00403
00404 if (limits.has_position_limits)
00405 {
00406 *lower_limit = limits.min_position;
00407 *upper_limit = limits.max_position;
00408 }
00409 if (limits.has_effort_limits)
00410 *effort_limit = limits.max_effort;
00411
00412 if (has_soft_limits)
00413 {
00414 switch (ctrl_method)
00415 {
00416 case EFFORT:
00417 {
00418 const joint_limits_interface::EffortJointSoftLimitsHandle
00419 limits_handle(joint_handle, limits, soft_limits);
00420 ej_limits_interface_.registerHandle(limits_handle);
00421 }
00422 break;
00423 case POSITION:
00424 {
00425 const joint_limits_interface::PositionJointSoftLimitsHandle
00426 limits_handle(joint_handle, limits, soft_limits);
00427 pj_limits_interface_.registerHandle(limits_handle);
00428 }
00429 break;
00430 case VELOCITY:
00431 {
00432 const joint_limits_interface::VelocityJointSoftLimitsHandle
00433 limits_handle(joint_handle, limits, soft_limits);
00434 vj_limits_interface_.registerHandle(limits_handle);
00435 }
00436 break;
00437 }
00438 }
00439 else
00440 {
00441 switch (ctrl_method)
00442 {
00443 case EFFORT:
00444 {
00445 const joint_limits_interface::EffortJointSaturationHandle
00446 sat_handle(joint_handle, limits);
00447 ej_sat_interface_.registerHandle(sat_handle);
00448 }
00449 break;
00450 case POSITION:
00451 {
00452 const joint_limits_interface::PositionJointSaturationHandle
00453 sat_handle(joint_handle, limits);
00454 pj_sat_interface_.registerHandle(sat_handle);
00455 }
00456 break;
00457 case VELOCITY:
00458 {
00459 const joint_limits_interface::VelocityJointSaturationHandle
00460 sat_handle(joint_handle, limits);
00461 vj_sat_interface_.registerHandle(sat_handle);
00462 }
00463 break;
00464 }
00465 }
00466 }
00467
00468
00469 void Armadillo2RobotHWSim::registerJointLimits(const std::string& joint_name,
00470 const hardware_interface::PosVelJointHandle& joint_handle,
00471 const ControlMethod ctrl_method,
00472 const ros::NodeHandle& joint_limit_nh,
00473 const urdf::Model *const urdf_model,
00474 int *const joint_type, double *const lower_limit,
00475 double *const upper_limit, double *const effort_limit)
00476 {
00477 *joint_type = urdf::Joint::UNKNOWN;
00478 *lower_limit = -std::numeric_limits<double>::max();
00479 *upper_limit = std::numeric_limits<double>::max();
00480 *effort_limit = std::numeric_limits<double>::max();
00481
00482 joint_limits_interface::JointLimits limits;
00483 bool has_limits = false;
00484 joint_limits_interface::SoftJointLimits soft_limits;
00485 bool has_soft_limits = false;
00486
00487 if (urdf_model != NULL)
00488 {
00489 const boost::shared_ptr<const urdf::Joint> urdf_joint = urdf_model->getJoint(joint_name);
00490 if (urdf_joint != NULL)
00491 {
00492 *joint_type = urdf_joint->type;
00493
00494 if (joint_limits_interface::getJointLimits(urdf_joint, limits))
00495 has_limits = true;
00496 if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits))
00497 has_soft_limits = true;
00498 }
00499 }
00500
00501 if (joint_limits_interface::getJointLimits(joint_name, joint_limit_nh, limits))
00502 has_limits = true;
00503
00504 if (!has_limits)
00505 return;
00506
00507 if (*joint_type == urdf::Joint::UNKNOWN)
00508 {
00509
00510
00511 if (limits.has_position_limits)
00512 {
00513 *joint_type = urdf::Joint::REVOLUTE;
00514 }
00515 else
00516 {
00517 if (limits.angle_wraparound)
00518 *joint_type = urdf::Joint::CONTINUOUS;
00519 else
00520 *joint_type = urdf::Joint::PRISMATIC;
00521 }
00522 }
00523
00524 if (limits.has_position_limits)
00525 {
00526 *lower_limit = limits.min_position;
00527 *upper_limit = limits.max_position;
00528 }
00529 if (limits.has_effort_limits)
00530 *effort_limit = limits.max_effort;
00531
00532
00533
00534
00535
00536
00537
00538
00539
00540
00541
00542
00543
00544
00545
00546
00547
00548
00549
00550
00551
00552
00553
00554
00555
00556
00557
00558
00559
00560
00561
00562
00563
00564
00565
00566
00567
00568
00569
00570
00571 }
00572
00573 PLUGINLIB_EXPORT_CLASS(gazebo_ros_control::Armadillo2RobotHWSim, gazebo_ros_control::RobotHWSim)
00574 }