1 #ifndef PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H 2 #define PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H 24 int positionChange)
override;
57 #endif // PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H int loops_without_update_speed_buffer
int speed_filter_idle_iter_loops_before_reset_
void display_properties()
void detachHandler() override
ros::NodeHandle nh_private_
std::vector< double > speeds_buffer
HighSpeedEncoderRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
ros::Publisher encoder_pub_
void timerCallback(const ros::TimerEvent &event)
std::vector< ros::Publisher > encoder_decimspeed_pubs_
std::vector< double > joint_tick2rad_
std::mutex encoder_states_mutex_
bool speed_buffer_updated
void positionChangeHandler(int index, int time, int positionChange) override
std::vector< TStatePerChannel > encoder_states_
void errorHandler(int errorCode) override
void attachHandler() override
double instantaneousSpeed
std::vector< std::string > joint_names_
int speed_filter_samples_len_