high_speed_encoder_ros_i.h
Go to the documentation of this file.
1 #ifndef PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H
2 #define PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H
3 
4 #include <mutex>
5 #include <vector>
6 
7 #include <ros/ros.h>
8 
9 #include <phidgets_api/encoder.h>
10 
11 namespace phidgets {
12 class HighSpeedEncoderRosI final : public Encoder
13 {
14  public:
16  ros::NodeHandle nh_private);
17 
18  private:
19  void attachHandler() override;
20  void detachHandler() override;
21  void errorHandler(int errorCode) override;
22 
23  void positionChangeHandler(int index, int time,
24  int positionChange) override;
25 
26  void display_properties();
27 
28  void timerCallback(const ros::TimerEvent& event);
29 
32 
36  int tickPos = 0;
37  double instantaneousSpeed = .0;
38  std::vector<double> speeds_buffer;
39  bool speed_buffer_updated = false;
41  };
42  std::vector<TStatePerChannel> encoder_states_;
44  std::vector<std::string> joint_names_;
45  std::vector<double> joint_tick2rad_;
46  std::vector<ros::Publisher> encoder_decimspeed_pubs_;
47  // (Default=10) Number of samples for the sliding window average filter of
48  // speeds.
50  // (Default=1) Number of "ITERATE" loops without any new encoder tick before
51  // resetting the filtered average velocities.
53  std::string frame_id_;
54 };
55 } // namespace phidgets
56 
57 #endif // PHIDGETS_HIGH_SPEED_ENCODER_HIGH_SPEED_ENCODER_ROS_I_H
HighSpeedEncoderRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
void timerCallback(const ros::TimerEvent &event)
std::vector< ros::Publisher > encoder_decimspeed_pubs_
void positionChangeHandler(int index, int time, int positionChange) override
std::vector< TStatePerChannel > encoder_states_
void errorHandler(int errorCode) override
std::vector< std::string > joint_names_


phidgets_high_speed_encoder
Author(s): Geoff Viola , José-Luis Blanco Claraco
autogenerated on Fri Apr 9 2021 02:56:06