kuka_eki_hw_interface.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, 3M
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 are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the copyright holder, nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 // Author: Brett Hemes (3M) <brhemes@mmm.com>
33 
34 
35 #ifndef KUKA_EKI_HW_INTERFACE
36 #define KUKA_EKI_HW_INTERFACE
37 
38 #include <vector>
39 #include <string>
40 
41 #include <boost/asio.hpp>
42 
43 #include <ros/ros.h>
48 
49 
51 {
52 
54 {
55 private:
57 
58  const unsigned int n_dof_ = 6;
59  std::vector<std::string> joint_names_;
60  std::vector<double> joint_position_;
61  std::vector<double> joint_velocity_;
62  std::vector<double> joint_effort_;
63  std::vector<double> joint_position_command_;
64 
65  // EKI
66  std::string eki_server_address_;
67  std::string eki_server_port_;
69  int eki_max_cmd_buff_len_ = 5; // by default, limit command buffer to 5 (size of advance run in KRL)
70 
71  // Timing
74  double loop_hz_;
75 
76  // Interfaces
79 
80  // EKI socket read/write
81  int eki_read_state_timeout_ = 5; // [s]; settable by parameter (default = 5)
82  boost::asio::io_service ios_;
83  boost::asio::deadline_timer deadline_;
84  boost::asio::ip::udp::endpoint eki_server_endpoint_;
85  boost::asio::ip::udp::socket eki_server_socket_;
87  static void eki_handle_receive(const boost::system::error_code &ec, size_t length,
88  boost::system::error_code* out_ec, size_t* out_length);
89  bool eki_read_state(std::vector<double> &joint_position, std::vector<double> &joint_velocity,
90  std::vector<double> &joint_effort, int &cmd_buff_len);
91  bool eki_write_command(const std::vector<double> &joint_position);
92 
93 public:
94 
97 
98  void init();
99  void start();
100  void read(const ros::Time &time, const ros::Duration &period);
101  void write(const ros::Time &time, const ros::Duration &period);
102 };
103 
104 } // namespace kuka_eki_hw_interface
105 
106 #endif // KUKA_EKI_HW_INTERFACE
bool eki_read_state(std::vector< double > &joint_position, std::vector< double > &joint_velocity, std::vector< double > &joint_effort, int &cmd_buff_len)
void read(const ros::Time &time, const ros::Duration &period)
static void eki_handle_receive(const boost::system::error_code &ec, size_t length, boost::system::error_code *out_ec, size_t *out_length)
hardware_interface::JointStateInterface joint_state_interface_
bool eki_write_command(const std::vector< double > &joint_position)
void write(const ros::Time &time, const ros::Duration &period)
hardware_interface::PositionJointInterface position_joint_interface_


kuka_eki_hw_interface
Author(s): Brett Hemes (3M)
autogenerated on Tue Oct 15 2019 03:33:29