37 #ifndef DYNAMIXEL_LOOP 38 #define DYNAMIXEL_LOOP 44 #include <boost/shared_ptr.hpp> 50 #include <controller_manager/controller_manager.h> 57 static const double BILLION = 1000000000.0;
71 void jsCallback(
const sensor_msgs::JointState::ConstPtr& js);
ros::Publisher torque_pub
static const double BILLION
ros::Timer _non_realtime_loop
boost::shared_ptr< dynamixel::DynamixelHardwareInterface > _hardware_interface
Abstract Hardware Interface for your robot.
ros::Duration _elapsed_time
void jsCallback(const sensor_msgs::JointState::ConstPtr &js)
ros::Duration _desired_update_freq
DynamixelLoop(ros::NodeHandle &nh, boost::shared_ptr< dynamixel::DynamixelHardwareInterface > hardware_interface)
boost::shared_ptr< controller_manager::ControllerManager > _controller_manager
void update(const ros::TimerEvent &e)
sensor_msgs::JointState joint_state
struct timespec _current_time
struct timespec _last_time
double _cycle_time_error_threshold