#include <epos_manager.h>
Public Member Functions | |
EposManager (hardware_interface::ActuatorStateInterface &asi, hardware_interface::VelocityActuatorInterface &avi, hardware_interface::PositionActuatorInterface &api, ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::vector< std::string > &motor_names) | |
bool | init () |
std::vector< boost::shared_ptr < Epos > > | motors () |
void | read () |
void | update_diagnostics () |
void | write () |
Private Attributes | |
hardware_interface::PositionActuatorInterface * | api_ |
hardware_interface::ActuatorStateInterface * | asi_ |
hardware_interface::VelocityActuatorInterface * | avi_ |
EposFactory | epos_factory |
std::vector< boost::shared_ptr < Epos > > | motors_ |
Definition at line 17 of file epos_manager.h.
epos_hardware::EposManager::EposManager | ( | hardware_interface::ActuatorStateInterface & | asi, |
hardware_interface::VelocityActuatorInterface & | avi, | ||
hardware_interface::PositionActuatorInterface & | api, | ||
ros::NodeHandle & | nh, | ||
ros::NodeHandle & | pnh, | ||
const std::vector< std::string > & | motor_names | ||
) |
Definition at line 6 of file epos_manager.cpp.
bool epos_hardware::EposManager::init | ( | ) |
Definition at line 21 of file epos_manager.cpp.
std::vector<boost::shared_ptr<Epos> > epos_hardware::EposManager::motors | ( | ) | [inline] |
Definition at line 28 of file epos_manager.h.
void epos_hardware::EposManager::read | ( | ) |
Definition at line 38 of file epos_manager.cpp.
Definition at line 32 of file epos_manager.cpp.
void epos_hardware::EposManager::write | ( | ) |
Definition at line 44 of file epos_manager.cpp.
Definition at line 35 of file epos_manager.h.
Definition at line 33 of file epos_manager.h.
Definition at line 34 of file epos_manager.h.
Definition at line 31 of file epos_manager.h.
std::vector<boost::shared_ptr<Epos> > epos_hardware::EposManager::motors_ [private] |
Definition at line 28 of file epos_manager.h.