00001 #ifndef EPOS_HARDWARE_EPOS_HARDWARE_H_ 00002 #define EPOS_HARDWARE_EPOS_HARDWARE_H_ 00003 00004 #include <ros/ros.h> 00005 #include <hardware_interface/actuator_command_interface.h> 00006 #include <hardware_interface/actuator_state_interface.h> 00007 #include <hardware_interface/robot_hw.h> 00008 #include <transmission_interface/robot_transmissions.h> 00009 #include <transmission_interface/transmission_interface_loader.h> 00010 #include "epos_hardware/utils.h" 00011 #include "epos_hardware/epos.h" 00012 #include "epos_hardware/epos_manager.h" 00013 00014 00015 namespace epos_hardware { 00016 00017 class EposHardware : public hardware_interface::RobotHW { 00018 public: 00019 EposHardware(ros::NodeHandle& nh, ros::NodeHandle& pnh, const std::vector<std::string>& motor_names); 00020 bool init(); 00021 void read(); 00022 void write(); 00023 void update_diagnostics(); 00024 private: 00025 hardware_interface::ActuatorStateInterface asi; 00026 hardware_interface::VelocityActuatorInterface avi; 00027 hardware_interface::PositionActuatorInterface api; 00028 00029 EposManager epos_manager_; 00030 00031 transmission_interface::RobotTransmissions robot_transmissions; 00032 boost::scoped_ptr<transmission_interface::TransmissionInterfaceLoader> transmission_loader; 00033 }; 00034 00035 } 00036 00037 00038 #endif