42 int main(
int argc,
char** argv)
46 ros::init(argc, argv,
"kuka_rsi_hardware_interface");
59 auto stopwatch_last = std::chrono::steady_clock::now();
60 auto stopwatch_now = stopwatch_last;
64 kuka_rsi_hw_interface.
start();
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;
77 if (!kuka_rsi_hw_interface.
read(timestamp, period))
79 ROS_FATAL_NAMED(
"kuka_hardware_interface",
"Failed to read state from robot. Shutting down!");
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;
90 controller_manager.
update(timestamp, period);
93 kuka_rsi_hw_interface.
write(timestamp, period);
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)
#define ROS_FATAL_NAMED(name,...)
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)