Go to the documentation of this file.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
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058 #include <ur_modern_driver/ur_hardware_interface.h>
00059
00060 namespace ros_control_ur {
00061
00062 UrHardwareInterface::UrHardwareInterface(ros::NodeHandle& nh, UrDriver* robot) :
00063 nh_(nh), robot_(robot) {
00064
00065 init();
00066
00067 max_vel_change_ = 0.12;
00068
00069 ROS_INFO_NAMED("ur_hardware_interface", "Loaded ur_hardware_interface.");
00070 }
00071
00072 void UrHardwareInterface::init() {
00073 ROS_INFO_STREAM_NAMED("ur_hardware_interface",
00074 "Reading rosparams from namespace: " << nh_.getNamespace());
00075
00076
00077 nh_.getParam("hardware_interface/joints", joint_names_);
00078 if (joint_names_.size() == 0) {
00079 ROS_FATAL_STREAM_NAMED("ur_hardware_interface",
00080 "No joints found on parameter server for controller, did you load the proper yaml file?" << " Namespace: " << nh_.getNamespace());
00081 exit(-1);
00082 }
00083 num_joints_ = joint_names_.size();
00084
00085
00086 joint_position_.resize(num_joints_);
00087 joint_velocity_.resize(num_joints_);
00088 joint_effort_.resize(num_joints_);
00089 joint_position_command_.resize(num_joints_);
00090 joint_velocity_command_.resize(num_joints_);
00091 prev_joint_velocity_command_.resize(num_joints_);
00092
00093
00094 for (std::size_t i = 0; i < num_joints_; ++i) {
00095 ROS_DEBUG_STREAM_NAMED("ur_hardware_interface",
00096 "Loading joint name: " << joint_names_[i]);
00097
00098
00099 joint_state_interface_.registerHandle(
00100 hardware_interface::JointStateHandle(joint_names_[i],
00101 &joint_position_[i], &joint_velocity_[i],
00102 &joint_effort_[i]));
00103
00104
00105 position_joint_interface_.registerHandle(
00106 hardware_interface::JointHandle(
00107 joint_state_interface_.getHandle(joint_names_[i]),
00108 &joint_position_command_[i]));
00109
00110
00111 velocity_joint_interface_.registerHandle(
00112 hardware_interface::JointHandle(
00113 joint_state_interface_.getHandle(joint_names_[i]),
00114 &joint_velocity_command_[i]));
00115 prev_joint_velocity_command_[i] = 0.;
00116 }
00117
00118
00119 force_torque_interface_.registerHandle(
00120 hardware_interface::ForceTorqueSensorHandle("wrench", "",
00121 robot_force_, robot_torque_));
00122
00123 registerInterface(&joint_state_interface_);
00124 registerInterface(&position_joint_interface_);
00125 registerInterface(&velocity_joint_interface_);
00126 registerInterface(&force_torque_interface_);
00127 velocity_interface_running_ = false;
00128 position_interface_running_ = false;
00129 }
00130
00131 void UrHardwareInterface::read() {
00132 std::vector<double> pos, vel, current, tcp;
00133 pos = robot_->rt_interface_->robot_state_->getQActual();
00134 vel = robot_->rt_interface_->robot_state_->getQdActual();
00135 current = robot_->rt_interface_->robot_state_->getIActual();
00136 tcp = robot_->rt_interface_->robot_state_->getTcpForce();
00137 for (std::size_t i = 0; i < num_joints_; ++i) {
00138 joint_position_[i] = pos[i];
00139 joint_velocity_[i] = vel[i];
00140 joint_effort_[i] = current[i];
00141 }
00142 for (std::size_t i = 0; i < 3; ++i) {
00143 robot_force_[i] = tcp[i];
00144 robot_torque_[i] = tcp[i + 3];
00145 }
00146
00147 }
00148
00149 void UrHardwareInterface::setMaxVelChange(double inp) {
00150 max_vel_change_ = inp;
00151 }
00152
00153 void UrHardwareInterface::write() {
00154 if (velocity_interface_running_) {
00155 std::vector<double> cmd;
00156
00157 cmd.resize(joint_velocity_command_.size());
00158 for (unsigned int i = 0; i < joint_velocity_command_.size(); i++) {
00159 cmd[i] = joint_velocity_command_[i];
00160 if (cmd[i] > prev_joint_velocity_command_[i] + max_vel_change_) {
00161 cmd[i] = prev_joint_velocity_command_[i] + max_vel_change_;
00162 } else if (cmd[i]
00163 < prev_joint_velocity_command_[i] - max_vel_change_) {
00164 cmd[i] = prev_joint_velocity_command_[i] - max_vel_change_;
00165 }
00166 prev_joint_velocity_command_[i] = cmd[i];
00167 }
00168 robot_->setSpeed(cmd[0], cmd[1], cmd[2], cmd[3], cmd[4], cmd[5], max_vel_change_*125);
00169 } else if (position_interface_running_) {
00170 robot_->servoj(joint_position_command_);
00171 }
00172 }
00173
00174 bool UrHardwareInterface::canSwitch(
00175 const std::list<hardware_interface::ControllerInfo> &start_list,
00176 const std::list<hardware_interface::ControllerInfo> &stop_list) const {
00177 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00178 start_list.begin(); controller_it != start_list.end();
00179 ++controller_it) {
00180 if (controller_it->hardware_interface
00181 == "hardware_interface::VelocityJointInterface") {
00182 if (velocity_interface_running_) {
00183 ROS_ERROR(
00184 "%s: An interface of that type (%s) is already running",
00185 controller_it->name.c_str(),
00186 controller_it->hardware_interface.c_str());
00187 return false;
00188 }
00189 if (position_interface_running_) {
00190 bool error = true;
00191 for (std::list<hardware_interface::ControllerInfo>::const_iterator stop_controller_it =
00192 stop_list.begin();
00193 stop_controller_it != stop_list.end();
00194 ++stop_controller_it) {
00195 if (stop_controller_it->hardware_interface
00196 == "hardware_interface::PositionJointInterface") {
00197 error = false;
00198 break;
00199 }
00200 }
00201 if (error) {
00202 ROS_ERROR(
00203 "%s (type %s) can not be run simultaneously with a PositionJointInterface",
00204 controller_it->name.c_str(),
00205 controller_it->hardware_interface.c_str());
00206 return false;
00207 }
00208 }
00209 } else if (controller_it->hardware_interface
00210 == "hardware_interface::PositionJointInterface") {
00211 if (position_interface_running_) {
00212 ROS_ERROR(
00213 "%s: An interface of that type (%s) is already running",
00214 controller_it->name.c_str(),
00215 controller_it->hardware_interface.c_str());
00216 return false;
00217 }
00218 if (velocity_interface_running_) {
00219 bool error = true;
00220 for (std::list<hardware_interface::ControllerInfo>::const_iterator stop_controller_it =
00221 stop_list.begin();
00222 stop_controller_it != stop_list.end();
00223 ++stop_controller_it) {
00224 if (stop_controller_it->hardware_interface
00225 == "hardware_interface::VelocityJointInterface") {
00226 error = false;
00227 break;
00228 }
00229 }
00230 if (error) {
00231 ROS_ERROR(
00232 "%s (type %s) can not be run simultaneously with a VelocityJointInterface",
00233 controller_it->name.c_str(),
00234 controller_it->hardware_interface.c_str());
00235 return false;
00236 }
00237 }
00238 }
00239 }
00240
00241
00242 return true;
00243 }
00244
00245 void UrHardwareInterface::doSwitch(
00246 const std::list<hardware_interface::ControllerInfo>& start_list,
00247 const std::list<hardware_interface::ControllerInfo>& stop_list) {
00248 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00249 stop_list.begin(); controller_it != stop_list.end();
00250 ++controller_it) {
00251 if (controller_it->hardware_interface
00252 == "hardware_interface::VelocityJointInterface") {
00253 velocity_interface_running_ = false;
00254 ROS_DEBUG("Stopping velocity interface");
00255 }
00256 if (controller_it->hardware_interface
00257 == "hardware_interface::PositionJointInterface") {
00258 position_interface_running_ = false;
00259 std::vector<double> tmp;
00260 robot_->closeServo(tmp);
00261 ROS_DEBUG("Stopping position interface");
00262 }
00263 }
00264 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it =
00265 start_list.begin(); controller_it != start_list.end();
00266 ++controller_it) {
00267 if (controller_it->hardware_interface
00268 == "hardware_interface::VelocityJointInterface") {
00269 velocity_interface_running_ = true;
00270 ROS_DEBUG("Starting velocity interface");
00271 }
00272 if (controller_it->hardware_interface
00273 == "hardware_interface::PositionJointInterface") {
00274 position_interface_running_ = true;
00275 robot_->uploadProg();
00276 ROS_DEBUG("Starting position interface");
00277 }
00278 }
00279
00280 }
00281
00282 }
00283