38 int main(
int argc,
char** argv)
40 ros::init(argc, argv,
"kuka_eki_hw_interface");
48 hardware_interface.
init();
53 auto stopwatch_last = std::chrono::steady_clock::now();
54 auto stopwatch_now = stopwatch_last;
58 hardware_interface.
start();
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;
69 hardware_interface.
read(timestamp, period);
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;
78 controller_manager.
update(timestamp, period);
81 hardware_interface.
write(timestamp, period);
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)
void write(const ros::Time &time, const ros::Duration &period)
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
int main(int argc, char **argv)