kuka_hardware_interface_node.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 int main(int argc, char** argv)
43 {
44  ROS_INFO_STREAM_NAMED("hardware_interface", "Starting hardware interface...");
45 
46  ros::init(argc, argv, "kuka_rsi_hardware_interface");
47 
48  ros::AsyncSpinner spinner(2);
49  spinner.start();
50 
51  ros::NodeHandle nh;
52 
54  kuka_rsi_hw_interface.configure();
55 
56  // Set up timers
57  ros::Time timestamp;
58  ros::Duration period;
59  auto stopwatch_last = std::chrono::steady_clock::now();
60  auto stopwatch_now = stopwatch_last;
61 
63 
64  kuka_rsi_hw_interface.start();
65 
66  // Get current time and elapsed time since last read
67  timestamp = ros::Time::now();
68  stopwatch_now = std::chrono::steady_clock::now();
69  period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
70  stopwatch_last = stopwatch_now;
71 
72  // Run as fast as possible
73  while (ros::ok())
74  //while (!g_quit)
75  {
76  // Receive current state from robot
77  if (!kuka_rsi_hw_interface.read(timestamp, period))
78  {
79  ROS_FATAL_NAMED("kuka_hardware_interface", "Failed to read state from robot. Shutting down!");
80  ros::shutdown();
81  }
82 
83  // Get current time and elapsed time since last read
84  timestamp = ros::Time::now();
85  stopwatch_now = std::chrono::steady_clock::now();
86  period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
87  stopwatch_last = stopwatch_now;
88 
89  // Update the controllers
90  controller_manager.update(timestamp, period);
91 
92  // Send new setpoint to robot
93  kuka_rsi_hw_interface.write(timestamp, period);
94  }
95 
96  spinner.stop();
97  ROS_INFO_STREAM_NAMED("hardware_interface", "Shutting down.");
98 
99  return 0;
100 
101 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
#define ROS_INFO_STREAM_NAMED(name, args)
Duration & fromSec(double t)
ROSCPP_DECL bool ok()
#define ROS_FATAL_NAMED(name,...)
static Time now()
ROSCPP_DECL void shutdown()
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
bool read(const ros::Time time, const ros::Duration period)
bool write(const ros::Time time, const ros::Duration period)


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