Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <kuka_rsi_hw_interface/kuka_hardware_interface.h>
00041
00042 int main(int argc, char** argv)
00043 {
00044 ROS_INFO_STREAM_NAMED("hardware_interface", "Starting hardware interface...");
00045
00046 ros::init(argc, argv, "kuka_rsi_hardware_interface");
00047
00048 ros::AsyncSpinner spinner(2);
00049 spinner.start();
00050
00051 ros::NodeHandle nh;
00052
00053 kuka_rsi_hw_interface::KukaHardwareInterface kuka_rsi_hw_interface;
00054 kuka_rsi_hw_interface.configure();
00055
00056
00057 ros::Time timestamp;
00058 ros::Duration period;
00059 auto stopwatch_last = std::chrono::steady_clock::now();
00060 auto stopwatch_now = stopwatch_last;
00061
00062 controller_manager::ControllerManager controller_manager(&kuka_rsi_hw_interface, nh);
00063
00064 kuka_rsi_hw_interface.start();
00065
00066
00067 timestamp = ros::Time::now();
00068 stopwatch_now = std::chrono::steady_clock::now();
00069 period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
00070 stopwatch_last = stopwatch_now;
00071
00072
00073 while (ros::ok())
00074
00075 {
00076
00077 if (!kuka_rsi_hw_interface.read(timestamp, period))
00078 {
00079 ROS_FATAL_NAMED("kuka_hardware_interface", "Failed to read state from robot. Shutting down!");
00080 ros::shutdown();
00081 }
00082
00083
00084 timestamp = ros::Time::now();
00085 stopwatch_now = std::chrono::steady_clock::now();
00086 period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
00087 stopwatch_last = stopwatch_now;
00088
00089
00090 controller_manager.update(timestamp, period);
00091
00092
00093 kuka_rsi_hw_interface.write(timestamp, period);
00094 }
00095
00096 spinner.stop();
00097 ROS_INFO_STREAM_NAMED("hardware_interface", "Shutting down.");
00098
00099 return 0;
00100
00101 }