kuka_eki_hw_interface_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2018, 3M
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 are met:
00009  *
00010  *      * Redistributions of source code must retain the above copyright
00011  *        notice, this list of conditions and the following disclaimer.
00012  *      * Redistributions in binary form must reproduce the above copyright
00013  *        notice, this list of conditions and the following disclaimer in the
00014  *        documentation and/or other materials provided with the distribution.
00015  *      * Neither the name of the copyright holder, nor the names of its
00016  *        contributors may be used to endorse or promote products derived
00017  *        from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 // Author: Brett Hemes (3M) <brhemes@mmm.com>
00033 
00034 #include <chrono>
00035 
00036 #include <kuka_eki_hw_interface/kuka_eki_hw_interface.h>
00037 
00038 int main(int argc, char** argv)
00039 {
00040   ros::init(argc, argv, "kuka_eki_hw_interface");
00041 
00042   ros::AsyncSpinner spinner(2);
00043   spinner.start();
00044 
00045   ros::NodeHandle nh;
00046 
00047   kuka_eki_hw_interface::KukaEkiHardwareInterface hardware_interface;
00048   hardware_interface.init();
00049 
00050   // Set up timers
00051   ros::Time timestamp;
00052   ros::Duration period;
00053   auto stopwatch_last = std::chrono::steady_clock::now();
00054   auto stopwatch_now = stopwatch_last;
00055 
00056   controller_manager::ControllerManager controller_manager(&hardware_interface, nh);
00057 
00058   hardware_interface.start();
00059 
00060   // Get current time and elapsed time since last read
00061   timestamp = ros::Time::now();
00062   stopwatch_now = std::chrono::steady_clock::now();
00063   period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
00064   stopwatch_last = stopwatch_now;
00065 
00066   while (ros::ok())
00067   {
00068     // Receive current state from robot
00069     hardware_interface.read(timestamp, period);
00070 
00071     // Get current time and elapsed time since last read
00072     timestamp = ros::Time::now();
00073     stopwatch_now = std::chrono::steady_clock::now();
00074     period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
00075     stopwatch_last = stopwatch_now;
00076 
00077     // Update the controllers
00078     controller_manager.update(timestamp, period);
00079 
00080     // Send new setpoint to robot
00081     hardware_interface.write(timestamp, period);
00082   }
00083 
00084   spinner.stop();
00085   ROS_INFO_STREAM_NAMED("kuka_eki_hw_interface", "Shutting down.");
00086 
00087   return 0;
00088 }


kuka_eki_hw_interface
Author(s): Brett Hemes (3M)
autogenerated on Thu Jun 6 2019 17:56:08