kuka_eki_hw_interface_node.cpp
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 #include <chrono>
35 
37 
38 int main(int argc, char** argv)
39 {
40  ros::init(argc, argv, "kuka_eki_hw_interface");
41 
42  ros::AsyncSpinner spinner(2);
43  spinner.start();
44 
45  ros::NodeHandle nh;
46 
48  hardware_interface.init();
49 
50  // Set up timers
51  ros::Time timestamp;
52  ros::Duration period;
53  auto stopwatch_last = std::chrono::steady_clock::now();
54  auto stopwatch_now = stopwatch_last;
55 
57 
58  hardware_interface.start();
59 
60  // Get current time and elapsed time since last read
61  timestamp = ros::Time::now();
62  stopwatch_now = std::chrono::steady_clock::now();
63  period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
64  stopwatch_last = stopwatch_now;
65 
66  while (ros::ok())
67  {
68  // Receive current state from robot
69  hardware_interface.read(timestamp, period);
70 
71  // Get current time and elapsed time since last read
72  timestamp = ros::Time::now();
73  stopwatch_now = std::chrono::steady_clock::now();
74  period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
75  stopwatch_last = stopwatch_now;
76 
77  // Update the controllers
78  controller_manager.update(timestamp, period);
79 
80  // Send new setpoint to robot
81  hardware_interface.write(timestamp, period);
82  }
83 
84  spinner.stop();
85  ROS_INFO_STREAM_NAMED("kuka_eki_hw_interface", "Shutting down.");
86 
87  return 0;
88 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO_STREAM_NAMED(name, args)
void read(const ros::Time &time, const ros::Duration &period)
Duration & fromSec(double t)
ROSCPP_DECL bool ok()
void write(const ros::Time &time, const ros::Duration &period)
static Time now()
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
int main(int argc, char **argv)


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