NetFT driver plugin for ethercat_hardware. More...
#include <netft.h>

Public Member Functions | |
| void | collectDiagnostics (EthercatCom *com) |
| void | construct (ros::NodeHandle &nh) |
| void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *) |
| int | initialize (pr2_hardware_interface::HardwareInterface *, bool) |
| NetFT () | |
| bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
| ~NetFT () | |
Protected Member Functions | |
| bool | tryPublish (const geometry_msgs::WrenchStamped &data) |
| bool | tryPublishOld (const geometry_msgs::WrenchStamped &data) |
Protected Attributes | |
| pr2_hardware_interface::AnalogIn | analog_in_ |
| AnalogIn struct where device will put data for realtime controllers. | |
| pr2_hardware_interface::HardwareInterface * | hw_ |
| ros::Time | last_publish_time_ |
| Last time NetFT data was published to ROS topic. Used to limit publishing rate. | |
| netft_rdt_driver::NetFTRDTDriver * | netft_driver_ |
| Driver interface to NetFT device. | |
| ros::NodeHandle | nh_ |
| NodeHandle to use when getting necessary parameters and publishing. | |
| realtime_tools::RealtimePublisher < geometry_msgs::WrenchStamped > * | pub_ |
| Publish NetFT data to. | |
| realtime_tools::RealtimePublisher < geometry_msgs::Wrench > * | pub_old_ |
| Wrench message type is deprecated. | |
| ros::Duration | publish_period_ |
| bool | should_publish_ |
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 |
| 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] |
realtime_tools::RealtimePublisher<geometry_msgs::WrenchStamped>* netft_ethercat_hardware::NetFT::pub_ [protected] |
realtime_tools::RealtimePublisher<geometry_msgs::Wrench>* netft_ethercat_hardware::NetFT::pub_old_ [protected] |
bool netft_ethercat_hardware::NetFT::should_publish_ [protected] |