kuka_hardware_interface.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014 Norwegian University of Science and Technology
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Norwegian University of Science and
18  * Technology, nor the names of its contributors may be used to
19  * endorse or promote products derived from this software without
20  * specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /*
37  * Author: Lars Tingelstad <lars.tingelstad@ntnu.no>
38  */
39 
41 
42 #include <stdexcept>
43 
44 
45 namespace kuka_rsi_hw_interface
46 {
47 
49  joint_position_(6, 0.0), joint_velocity_(6, 0.0), joint_effort_(6, 0.0), joint_position_command_(6, 0.0), joint_velocity_command_(
50  6, 0.0), joint_effort_command_(6, 0.0), joint_names_(6), rsi_initial_joint_positions_(6, 0.0), rsi_joint_position_corrections_(
51  6, 0.0), ipoc_(0), n_dof_(6)
52 {
53  in_buffer_.resize(1024);
54  out_buffer_.resize(1024);
55  remote_host_.resize(1024);
56  remote_port_.resize(1024);
57 
58  if (!nh_.getParam("controller_joint_names", joint_names_))
59  {
60  ROS_ERROR("Cannot find required parameter 'controller_joint_names' "
61  "on the parameter server.");
62  throw std::runtime_error("Cannot find required parameter "
63  "'controller_joint_names' on the parameter server.");
64  }
65 
66  //Create ros_control interfaces
67  for (std::size_t i = 0; i < n_dof_; ++i)
68  {
69  // Create joint state interface for all joints
72  &joint_effort_[i]));
73 
74  // Create joint position control interface
78  }
79 
80  // Register interfaces
83 
84  ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded kuka_rsi_hardware_interface");
85 }
86 
88 {
89 
90 }
91 
92 bool KukaHardwareInterface::read(const ros::Time time, const ros::Duration period)
93 {
94  in_buffer_.resize(1024);
95 
96  if (server_->recv(in_buffer_) == 0)
97  {
98  return false;
99  }
100 
101  if (rt_rsi_pub_->trylock()){
102  rt_rsi_pub_->msg_.data = in_buffer_;
103  rt_rsi_pub_->unlockAndPublish();
104  }
105 
107  for (std::size_t i = 0; i < n_dof_; ++i)
108  {
110  }
112 
113  return true;
114 }
115 
117 {
118  out_buffer_.resize(1024);
119 
120  for (std::size_t i = 0; i < n_dof_; ++i)
121  {
123  }
124 
126  server_->send(out_buffer_);
127 
128  return true;
129 }
130 
132 {
133  // Wait for connection from robot
135 
136  ROS_INFO_STREAM_NAMED("kuka_hardware_interface", "Waiting for robot!");
137 
138  int bytes = server_->recv(in_buffer_);
139 
140  // Drop empty <rob> frame with RSI <= 2.3
141  if (bytes < 100)
142  {
143  bytes = server_->recv(in_buffer_);
144  }
145 
147  for (std::size_t i = 0; i < n_dof_; ++i)
148  {
152  }
155  server_->send(out_buffer_);
156  // Set receive timeout to 1 second
157  server_->set_timeout(1000);
158  ROS_INFO_STREAM_NAMED("kuka_hardware_interface", "Got connection from robot");
159 
160 }
161 
163 {
164  const std::string param_addr = "rsi/listen_address";
165  const std::string param_port = "rsi/listen_port";
166 
167  if (nh_.getParam(param_addr, local_host_) && nh_.getParam(param_port, local_port_))
168  {
169  ROS_INFO_STREAM_NAMED("kuka_hardware_interface",
170  "Setting up RSI server on: (" << local_host_ << ", " << local_port_ << ")");
171  }
172  else
173  {
174  std::string msg = "Failed to get RSI listen address or listen port from"
175  " parameter server (looking for '" + param_addr + "' and '" + param_port + "')";
176  ROS_ERROR_STREAM(msg);
177  throw std::runtime_error(msg);
178  }
180 }
181 
182 } // namespace kuka_rsi_hardware_interface
std::vector< double > positions
Definition: rsi_state.h:66
static const double DEG2RAD
#define ROS_INFO_STREAM_NAMED(name, args)
static const double RAD2DEG
hardware_interface::PositionJointInterface position_joint_interface_
std::unique_ptr< realtime_tools::RealtimePublisher< std_msgs::String > > rt_rsi_pub_
unsigned long long ipoc
Definition: rsi_state.h:74
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
hardware_interface::JointStateInterface joint_state_interface_
#define ROS_ERROR(...)
bool read(const ros::Time time, const ros::Duration period)
bool write(const ros::Time time, const ros::Duration period)
std::vector< double > initial_positions
Definition: rsi_state.h:68


kuka_rsi_hw_interface
Author(s): Lars Tingelstad
autogenerated on Tue Oct 15 2019 03:33:54