$search
NetFT driver plugin for ethercat_hardware. More...
#include <netft.h>
NetFT driver plugin for ethercat_hardware.
This driver allows data published by NetFT over UDP to be available to realtime controllers as analog inputs. This driver also publishes data to ROS topic.
address | IPV4 address for NetFT box. Example "192.168.1.1". | |
ros_publish_period | Period in seconds that plugin will publish force/torqe data to ROS topic | |
analog_in_name | Name to use when registering AnalogIn that contains force/torque data |
Definition at line 65 of file netft.h.
void netft_ethercat_hardware::NetFT::collectDiagnostics | ( | EthercatCom * | com | ) | [virtual] |
Reimplemented from EthercatDevice.
void netft_ethercat_hardware::NetFT::construct | ( | ros::NodeHandle & | nh | ) | [virtual] |
Reimplemented from EthercatDevice.
void netft_ethercat_hardware::NetFT::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, | |
unsigned char * | ||||
) | [virtual] |
Reimplemented from EthercatDevice.
int netft_ethercat_hardware::NetFT::initialize | ( | pr2_hardware_interface::HardwareInterface * | hw, | |
bool | ||||
) | [virtual] |
Implements EthercatDevice.
bool netft_ethercat_hardware::NetFT::tryPublish | ( | const geometry_msgs::WrenchStamped & | data | ) | [protected] |
bool netft_ethercat_hardware::NetFT::tryPublishOld | ( | const geometry_msgs::WrenchStamped & | data | ) | [protected] |
bool netft_ethercat_hardware::NetFT::unpackState | ( | unsigned char * | this_buffer, | |
unsigned char * | prev_buffer | |||
) | [virtual] |
Reimplemented from EthercatDevice.
ros::NodeHandle netft_ethercat_hardware::NetFT::nh_ [protected] |
bool netft_ethercat_hardware::NetFT::should_publish_ [protected] |