Unified hexapod repository, containing all modules
您最多选择25个主题 主题必须以字母或数字开头,可以包含连字符 (-),并且长度不得超过35个字符

92 行
3.1KB

  1. #ifndef HEXAPOD_ROBOT_HWI_
  2. #define HEXAPOD_ROBOT_HWI_
  3. #include <memory>
  4. #include <string>
  5. #include <vector>
  6. #include <unordered_set>
  7. #include <map>
  8. #include "hardware_interface/handle.hpp"
  9. #include "hardware_interface/hardware_info.hpp"
  10. #include "hardware_interface/system_interface.hpp"
  11. #include "hardware_interface/types/hardware_interface_return_values.hpp"
  12. #include "rclcpp/macros.hpp"
  13. #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
  14. #include "rclcpp_lifecycle/state.hpp"
  15. namespace hexapod_robot {
  16. struct PWMOutput {
  17. uint8_t i2c_address;
  18. uint8_t channel;
  19. double counts_intersect;
  20. double counts_slope;
  21. double counts_min;
  22. double counts_max;
  23. };
  24. class HexapodRobotHardwareInterface : public hardware_interface::SystemInterface {
  25. public:
  26. RCLCPP_SHARED_PTR_DEFINITIONS(HexapodRobotHardwareInterface)
  27. virtual ~HexapodRobotHardwareInterface();
  28. hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override;
  29. std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
  30. std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
  31. hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override;
  32. hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
  33. hardware_interface::return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;
  34. hardware_interface::return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) override;
  35. private:
  36. bool servos_powered_;
  37. std::map<std::string, double> joint_commands_;
  38. std::map<std::string, PWMOutput> joint_pwm_mapping_;
  39. bool i2c_available_;
  40. int i2c_fd_;
  41. std::map<uint8_t, bool> pca_available_;
  42. bool i2c_open_(const std::string& device);
  43. const uint8_t pca_reg_mode1_ = 0x00;
  44. const uint8_t pca_reg_mode2_ = 0x01;
  45. const uint8_t pca_reg_prescale_ = 0xfe;
  46. // base address for LED0 following,
  47. // other channels can be calculated by adding
  48. // channel_number * 4
  49. // to each base address
  50. const uint8_t pca_reg_led_on_l_ = 0x06;
  51. const uint8_t pca_reg_led_on_h_ = 0x07;
  52. const uint8_t pca_reg_led_off_l_ = 0x08;
  53. const uint8_t pca_reg_led_off_h_ = 0x09;
  54. const uint8_t pca_mode1_sleep_ = 0x10;
  55. const uint8_t pca_mode1_restart_ = 0x80;
  56. const uint8_t pca_mode2_outdrv_ = 0x04;
  57. const double pca_osc_frequency_ = 25000000; // 25 Mhz
  58. const double pca_pwm_frequency_ = 50; // 50 Hz
  59. const double pca_prescaler_value_ = (pca_osc_frequency_ / (4096.0 * pca_pwm_frequency_) - 0.5); // according to data sheet
  60. const double pca_pwm_cycle_usec_ = 1000000 / pca_pwm_frequency_; // microseconds per PWM counter cycle
  61. const double pca_pwm_count_usec_ = pca_pwm_cycle_usec_ / 4096; // microseconds per PWM single count
  62. void pca_initialize_();
  63. bool pca_set_pwm_(uint8_t i2c_address, uint8_t channel_number, uint16_t counts);
  64. };
  65. } // namespace
  66. #endif // HEXAPOD_ROBOT_HWI_