00001 #ifndef EPOS_HARDWARE_EPOS_MANAGER_H_ 00002 #define EPOS_HARDWARE_EPOS_MANAGER_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 <diagnostic_updater/diagnostic_updater.h> 00011 #include "epos_hardware/utils.h" 00012 #include "epos_hardware/epos.h" 00013 00014 00015 namespace epos_hardware { 00016 00017 class EposManager { 00018 public: 00019 EposManager(hardware_interface::ActuatorStateInterface& asi, 00020 hardware_interface::VelocityActuatorInterface& avi, 00021 hardware_interface::PositionActuatorInterface& api, 00022 ros::NodeHandle& nh, ros::NodeHandle& pnh, 00023 const std::vector<std::string>& motor_names); 00024 bool init(); 00025 void read(); 00026 void write(); 00027 void update_diagnostics(); 00028 std::vector<boost::shared_ptr<Epos> > motors() { return motors_; }; 00029 private: 00030 std::vector<boost::shared_ptr<Epos> > motors_; 00031 EposFactory epos_factory; 00032 00033 hardware_interface::ActuatorStateInterface* asi_; 00034 hardware_interface::VelocityActuatorInterface* avi_; 00035 hardware_interface::PositionActuatorInterface* api_; 00036 }; 00037 00038 } 00039 00040 00041 #endif