Definition at line 21 of file cirkit_unit03_hw.cpp.
CirkitUnit03HardwareInterface::CirkitUnit03HardwareInterface | ( | const std::string & | imcs01_port, |
const ros::NodeHandle & | nh | ||
) |
Definition at line 61 of file cirkit_unit03_hw.cpp.
ros::Duration CirkitUnit03HardwareInterface::getPeriod | ( | ) | const [inline] |
Definition at line 27 of file cirkit_unit03_hw.cpp.
ros::Time CirkitUnit03HardwareInterface::getTime | ( | ) | const [inline] |
Definition at line 26 of file cirkit_unit03_hw.cpp.
void CirkitUnit03HardwareInterface::publishSteer | ( | double | angle_cmd | ) | [protected] |
Definition at line 141 of file cirkit_unit03_hw.cpp.
void CirkitUnit03HardwareInterface::read | ( | ) |
Definition at line 110 of file cirkit_unit03_hw.cpp.
void CirkitUnit03HardwareInterface::registerVirtualJointState | ( | std::vector< double > & | virtual_wheels_pos_, |
std::vector< double > & | virtual_wheels_vel_, | ||
std::vector< double > & | virtual_wheels_eff_, | ||
std::vector< std::string > & | virtual_wheels_names | ||
) | [protected] |
Definition at line 99 of file cirkit_unit03_hw.cpp.
void CirkitUnit03HardwareInterface::write | ( | ) |
Definition at line 135 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::front_steer_eff_ [protected] |
Definition at line 41 of file cirkit_unit03_hw.cpp.
hardware_interface::PositionJointInterface CirkitUnit03HardwareInterface::front_steer_jnt_pos_cmd_interface_ [protected] |
Definition at line 38 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::front_steer_pos_ [protected] |
Definition at line 39 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::front_steer_pos_cmd_ [protected] |
Definition at line 42 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::front_steer_vel_ [protected] |
Definition at line 40 of file cirkit_unit03_hw.cpp.
Definition at line 58 of file cirkit_unit03_hw.cpp.
hardware_interface::JointStateInterface CirkitUnit03HardwareInterface::joint_state_interface_ [protected] |
Definition at line 51 of file cirkit_unit03_hw.cpp.
ros::NodeHandle CirkitUnit03HardwareInterface::nh_ [protected] |
Definition at line 36 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::rear_wheel_eff_ [protected] |
Definition at line 48 of file cirkit_unit03_hw.cpp.
hardware_interface::VelocityJointInterface CirkitUnit03HardwareInterface::rear_wheel_jnt_vel_cmd_interface_ [protected] |
Definition at line 45 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::rear_wheel_pos_ [protected] |
Definition at line 46 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::rear_wheel_vel_ [protected] |
Definition at line 47 of file cirkit_unit03_hw.cpp.
double CirkitUnit03HardwareInterface::rear_wheel_vel_cmd_ [protected] |
Definition at line 49 of file cirkit_unit03_hw.cpp.
Definition at line 57 of file cirkit_unit03_hw.cpp.
std::vector<double> CirkitUnit03HardwareInterface::virtual_wheels_eff_ [protected] |
Definition at line 55 of file cirkit_unit03_hw.cpp.
std::vector<double> CirkitUnit03HardwareInterface::virtual_wheels_pos_ [protected] |
Definition at line 53 of file cirkit_unit03_hw.cpp.
std::vector<double> CirkitUnit03HardwareInterface::virtual_wheels_vel_ [protected] |
Definition at line 54 of file cirkit_unit03_hw.cpp.