60 template <
class Protocol>
69 _hardware_interface(hardware_interface)
77 error += !np.
getParam(
"loop_frequency", _loop_hz);
78 error += !np.
getParam(
"cycle_time_error_threshold", _cycle_time_error_threshold);
80 char error_message[] =
"could not retrieve one of the required parameters\n\tdynamixel_hw/loop_hz or dynamixel_hw/cycle_time_error_threshold";
82 throw std::runtime_error(error_message);
86 _last_time = steady_clock::now();
103 _current_time = steady_clock::now();
104 duration<double> time_span
105 = duration_cast<duration<double>>(_current_time - _last_time);
107 _last_time = _current_time;
110 const double cycle_time_error = (_elapsed_time - _desired_update_freq).toSec();
111 if (cycle_time_error > _cycle_time_error_threshold) {
113 << cycle_time_error - _cycle_time_error_threshold <<
"s, " 114 <<
"cycle time: " << _elapsed_time <<
"s, " 115 <<
"threshold: " << _cycle_time_error_threshold <<
"s");
ros::Duration _elapsed_time
steady_clock::time_point _current_time
std::shared_ptr< controller_manager::ControllerManager > _controller_manager
steady_clock::time_point _last_time
std::shared_ptr< hw_int > _hardware_interface
Abstract Hardware Interface for your robot.
double _cycle_time_error_threshold
ros::Duration _desired_update_freq
typename dynamixel::DynamixelHardwareInterface< Protocol > hw_int
DynamixelLoop(ros::NodeHandle &nh, std::shared_ptr< hw_int > hardware_interface)
#define ROS_WARN_STREAM(args)
void update(const ros::TimerEvent &)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
ros::Timer _non_realtime_loop