$search

netft_ethercat_hardware::NetFT Class Reference

NetFT driver plugin for ethercat_hardware. More...

#include <netft.h>

Inheritance diagram for netft_ethercat_hardware::NetFT:
Inheritance graph
[legend]

List of all members.

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::HardwareInterfacehw_
ros::Time last_publish_time_
 Last time NetFT data was published to ROS topic. Used to limit publishing rate.
netft_rdt_driver::NetFTRDTDrivernetft_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_

Detailed Description

NetFT driver plugin for ethercat_hardware.

Author:
Derek King NetFT is analog converter for Force/Torque sensors from ATI IA. http://www.ati-ia.com/products/ft/ft_NetFT.aspx

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.

ROS interface

Parameters:
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.


Constructor & Destructor Documentation

netft_ethercat_hardware::NetFT::NetFT (  ) 

Definition at line 51 of file netft.cpp.

netft_ethercat_hardware::NetFT::~NetFT (  ) 

Definition at line 60 of file netft.cpp.


Member Function Documentation

void netft_ethercat_hardware::NetFT::collectDiagnostics ( EthercatCom com  )  [virtual]

Reimplemented from EthercatDevice.

Definition at line 208 of file netft.cpp.

void netft_ethercat_hardware::NetFT::construct ( ros::NodeHandle nh  )  [virtual]

Reimplemented from EthercatDevice.

Definition at line 67 of file netft.cpp.

void netft_ethercat_hardware::NetFT::diagnostics ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *   
) [virtual]

Reimplemented from EthercatDevice.

Definition at line 213 of file netft.cpp.

int netft_ethercat_hardware::NetFT::initialize ( pr2_hardware_interface::HardwareInterface hw,
bool   
) [virtual]

Implements EthercatDevice.

Definition at line 72 of file netft.cpp.

bool netft_ethercat_hardware::NetFT::tryPublish ( const geometry_msgs::WrenchStamped data  )  [protected]

Definition at line 173 of file netft.cpp.

bool netft_ethercat_hardware::NetFT::tryPublishOld ( const geometry_msgs::WrenchStamped data  )  [protected]

Definition at line 190 of file netft.cpp.

bool netft_ethercat_hardware::NetFT::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
) [virtual]

Reimplemented from EthercatDevice.

Definition at line 141 of file netft.cpp.


Member Data Documentation

AnalogIn struct where device will put data for realtime controllers.

Definition at line 87 of file netft.h.

Definition at line 78 of file netft.h.

Last time NetFT data was published to ROS topic. Used to limit publishing rate.

Definition at line 94 of file netft.h.

Driver interface to NetFT device.

Definition at line 84 of file netft.h.

NodeHandle to use when getting necessary parameters and publishing.

Definition at line 81 of file netft.h.

Publish NetFT data to.

Definition at line 90 of file netft.h.

Wrench message type is deprecated.

Definition at line 91 of file netft.h.

Definition at line 95 of file netft.h.

Definition at line 96 of file netft.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


netft_ethercat_hardware
Author(s): Derek King
autogenerated on Fri Mar 1 16:12:04 2013