kuka_hardware_interface.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014 Norwegian University of Science and Technology
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Norwegian University of Science and
00018  *     Technology, nor the names of its contributors may be used to
00019  *     endorse or promote products derived from this software without
00020  *     specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /*
00037  * Author: Lars Tingelstad <lars.tingelstad@ntnu.no>
00038  */
00039 
00040 #include <kuka_rsi_hw_interface/kuka_hardware_interface.h>
00041 
00042 #include <stdexcept>
00043 
00044 
00045 namespace kuka_rsi_hw_interface
00046 {
00047 
00048 KukaHardwareInterface::KukaHardwareInterface() :
00049     joint_position_(6, 0.0), joint_velocity_(6, 0.0), joint_effort_(6, 0.0), joint_position_command_(6, 0.0), joint_velocity_command_(
00050         6, 0.0), joint_effort_command_(6, 0.0), joint_names_(6), rsi_initial_joint_positions_(6, 0.0), rsi_joint_position_corrections_(
00051         6, 0.0), ipoc_(0), n_dof_(6)
00052 {
00053   in_buffer_.resize(1024);
00054   out_buffer_.resize(1024);
00055   remote_host_.resize(1024);
00056   remote_port_.resize(1024);
00057 
00058   if (!nh_.getParam("controller_joint_names", joint_names_))
00059   {
00060     ROS_ERROR("Cannot find required parameter 'controller_joint_names' "
00061       "on the parameter server.");
00062     throw std::runtime_error("Cannot find required parameter "
00063       "'controller_joint_names' on the parameter server.");
00064   }
00065 
00066   //Create ros_control interfaces
00067   for (std::size_t i = 0; i < n_dof_; ++i)
00068   {
00069     // Create joint state interface for all joints
00070     joint_state_interface_.registerHandle(
00071         hardware_interface::JointStateHandle(joint_names_[i], &joint_position_[i], &joint_velocity_[i],
00072                                              &joint_effort_[i]));
00073 
00074     // Create joint position control interface
00075     position_joint_interface_.registerHandle(
00076         hardware_interface::JointHandle(joint_state_interface_.getHandle(joint_names_[i]),
00077                                         &joint_position_command_[i]));
00078   }
00079 
00080   // Register interfaces
00081   registerInterface(&joint_state_interface_);
00082   registerInterface(&position_joint_interface_);
00083 
00084   ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded kuka_rsi_hardware_interface");
00085 }
00086 
00087 KukaHardwareInterface::~KukaHardwareInterface()
00088 {
00089 
00090 }
00091 
00092 bool KukaHardwareInterface::read(const ros::Time time, const ros::Duration period)
00093 {
00094   in_buffer_.resize(1024);
00095 
00096   if (server_->recv(in_buffer_) == 0)
00097   {
00098     return false;
00099   }
00100 
00101   if (rt_rsi_pub_->trylock()){
00102     rt_rsi_pub_->msg_.data = in_buffer_;
00103     rt_rsi_pub_->unlockAndPublish();
00104   }
00105 
00106   rsi_state_ = RSIState(in_buffer_);
00107   for (std::size_t i = 0; i < n_dof_; ++i)
00108   {
00109     joint_position_[i] = DEG2RAD * rsi_state_.positions[i];
00110   }
00111   ipoc_ = rsi_state_.ipoc;
00112 
00113   return true;
00114 }
00115 
00116 bool KukaHardwareInterface::write(const ros::Time time, const ros::Duration period)
00117 {
00118   out_buffer_.resize(1024);
00119 
00120   for (std::size_t i = 0; i < n_dof_; ++i)
00121   {
00122     rsi_joint_position_corrections_[i] = (RAD2DEG * joint_position_command_[i]) - rsi_initial_joint_positions_[i];
00123   }
00124 
00125   out_buffer_ = RSICommand(rsi_joint_position_corrections_, ipoc_).xml_doc;
00126   server_->send(out_buffer_);
00127 
00128   return true;
00129 }
00130 
00131 void KukaHardwareInterface::start()
00132 {
00133   // Wait for connection from robot
00134   server_.reset(new UDPServer(local_host_, local_port_));
00135 
00136   ROS_INFO_STREAM_NAMED("kuka_hardware_interface", "Waiting for robot!");
00137 
00138   int bytes = server_->recv(in_buffer_);
00139 
00140   // Drop empty <rob> frame with RSI <= 2.3
00141   if (bytes < 100)
00142   {
00143     bytes = server_->recv(in_buffer_);
00144   }
00145 
00146   rsi_state_ = RSIState(in_buffer_);
00147   for (std::size_t i = 0; i < n_dof_; ++i)
00148   {
00149     joint_position_[i] = DEG2RAD * rsi_state_.positions[i];
00150     joint_position_command_[i] = joint_position_[i];
00151     rsi_initial_joint_positions_[i] = rsi_state_.initial_positions[i];
00152   }
00153   ipoc_ = rsi_state_.ipoc;
00154   out_buffer_ = RSICommand(rsi_joint_position_corrections_, ipoc_).xml_doc;
00155   server_->send(out_buffer_);
00156   // Set receive timeout to 1 second
00157   server_->set_timeout(1000);
00158   ROS_INFO_STREAM_NAMED("kuka_hardware_interface", "Got connection from robot");
00159 
00160 }
00161 
00162 void KukaHardwareInterface::configure()
00163 {
00164   const std::string param_addr = "rsi/listen_address";
00165   const std::string param_port = "rsi/listen_port";
00166 
00167   if (nh_.getParam(param_addr, local_host_) && nh_.getParam(param_port, local_port_))
00168   {
00169     ROS_INFO_STREAM_NAMED("kuka_hardware_interface",
00170                           "Setting up RSI server on: (" << local_host_ << ", " << local_port_ << ")");
00171   }
00172   else
00173   {
00174     std::string msg = "Failed to get RSI listen address or listen port from"
00175     " parameter server (looking for '" + param_addr + "' and '" + param_port + "')";
00176     ROS_ERROR_STREAM(msg);
00177     throw std::runtime_error(msg);
00178   }
00179   rt_rsi_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::String>(nh_, "rsi_xml_doc", 3));
00180 }
00181 
00182 } // namespace kuka_rsi_hardware_interface


kuka_rsi_hw_interface
Author(s): Lars Tingelstad
autogenerated on Thu Jun 6 2019 17:56:48