35 #ifndef KUKA_EKI_HW_INTERFACE 36 #define KUKA_EKI_HW_INTERFACE 41 #include <boost/asio.hpp> 82 boost::asio::io_service
ios_;
88 boost::system::error_code* out_ec,
size_t* out_length);
89 bool eki_read_state(std::vector<double> &joint_position, std::vector<double> &joint_velocity,
90 std::vector<double> &joint_effort,
int &cmd_buff_len);
106 #endif // KUKA_EKI_HW_INTERFACE std::vector< std::string > joint_names_
int eki_max_cmd_buff_len_
int eki_read_state_timeout_
bool eki_read_state(std::vector< double > &joint_position, std::vector< double > &joint_velocity, std::vector< double > &joint_effort, int &cmd_buff_len)
KukaEkiHardwareInterface()
boost::asio::deadline_timer deadline_
void read(const ros::Time &time, const ros::Duration &period)
boost::asio::io_service ios_
boost::asio::ip::udp::socket eki_server_socket_
boost::asio::ip::udp::endpoint eki_server_endpoint_
std::vector< double > joint_position_command_
~KukaEkiHardwareInterface()
static void eki_handle_receive(const boost::system::error_code &ec, size_t length, boost::system::error_code *out_ec, size_t *out_length)
ros::Duration control_period_
hardware_interface::JointStateInterface joint_state_interface_
bool eki_write_command(const std::vector< double > &joint_position)
ros::Duration elapsed_time_
void write(const ros::Time &time, const ros::Duration &period)
std::vector< double > joint_effort_
std::string eki_server_address_
void eki_check_read_state_deadline()
std::vector< double > joint_position_
const unsigned int n_dof_
hardware_interface::PositionJointInterface position_joint_interface_
std::string eki_server_port_
std::vector< double > joint_velocity_