#include <netft_rdt_driver.h>
Public Member Functions | |
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d) |
Add device diagnostics status wrapper. More... | |
void | getData (geometry_msgs::WrenchStamped &data) |
Get newest RDT data from netFT device. More... | |
NetFTRDTDriver (const std::string &address) | |
bool | waitForNewData (void) |
Wait for new NetFT data to arrive. More... | |
~NetFTRDTDriver () | |
Protected Types | |
enum | { RDT_PORT =49152 } |
Protected Member Functions | |
void | recvThreadFunc (void) |
void | startStreaming (void) |
Asks NetFT to start streaming data. More... | |
Protected Attributes | |
std::string | address_ |
boost::condition | condition_ |
unsigned | diag_packet_count_ |
Packet count last time diagnostics thread published output. More... | |
double | force_scale_ |
Scaling factor for converting raw force values from device into Newtons. More... | |
boost::asio::io_service | io_service_ |
ros::Time | last_diag_pub_time_ |
Last time diagnostics was published. More... | |
uint32_t | last_rdt_sequence_ |
to keep track of out-of-order or duplicate packet More... | |
unsigned | lost_packets_ |
Count of lost RDT packets using RDT sequence number. More... | |
boost::mutex | mutex_ |
geometry_msgs::WrenchStamped | new_data_ |
Newest data received from netft device. More... | |
unsigned | out_of_order_count_ |
Counts number of out-of-order (or duplicate) received packets. More... | |
unsigned | packet_count_ |
Count number of received <good> packets. More... | |
boost::thread | recv_thread_ |
std::string | recv_thread_error_msg_ |
Set if recv thread exited because of error. More... | |
bool | recv_thread_running_ |
True if recv loop is still running. More... | |
unsigned | seq_counter_ |
Incremental counter for wrench header. More... | |
boost::asio::ip::udp::socket | socket_ |
volatile bool | stop_recv_thread_ |
uint32_t | system_status_ |
to keep track of any error codes reported by netft More... | |
double | torque_scale_ |
Scaling factor for converting raw torque values into Newton*meters. More... | |
Definition at line 50 of file netft_rdt_driver.h.
|
protected |
Enumerator | |
---|---|
RDT_PORT |
Definition at line 74 of file netft_rdt_driver.h.
netft_rdt_driver::NetFTRDTDriver::NetFTRDTDriver | ( | const std::string & | address | ) |
Definition at line 128 of file netft_rdt_driver.cpp.
netft_rdt_driver::NetFTRDTDriver::~NetFTRDTDriver | ( | ) |
Definition at line 177 of file netft_rdt_driver.cpp.
void netft_rdt_driver::NetFTRDTDriver::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d | ) |
Add device diagnostics status wrapper.
Definition at line 294 of file netft_rdt_driver.cpp.
void netft_rdt_driver::NetFTRDTDriver::getData | ( | geometry_msgs::WrenchStamped & | data | ) |
Get newest RDT data from netFT device.
Definition at line 286 of file netft_rdt_driver.cpp.
|
protected |
Definition at line 224 of file netft_rdt_driver.cpp.
|
protected |
Asks NetFT to start streaming data.
Definition at line 210 of file netft_rdt_driver.cpp.
bool netft_rdt_driver::NetFTRDTDriver::waitForNewData | ( | void | ) |
Wait for new NetFT data to arrive.
Definition at line 195 of file netft_rdt_driver.cpp.
|
protected |
Definition at line 75 of file netft_rdt_driver.h.
|
protected |
Definition at line 81 of file netft_rdt_driver.h.
|
protected |
Packet count last time diagnostics thread published output.
Definition at line 105 of file netft_rdt_driver.h.
|
protected |
Scaling factor for converting raw force values from device into Newtons.
Definition at line 100 of file netft_rdt_driver.h.
|
protected |
Definition at line 77 of file netft_rdt_driver.h.
|
protected |
Last time diagnostics was published.
Definition at line 107 of file netft_rdt_driver.h.
|
protected |
to keep track of out-of-order or duplicate packet
Definition at line 110 of file netft_rdt_driver.h.
|
protected |
Count of lost RDT packets using RDT sequence number.
Definition at line 93 of file netft_rdt_driver.h.
|
protected |
Definition at line 79 of file netft_rdt_driver.h.
|
protected |
Newest data received from netft device.
Definition at line 89 of file netft_rdt_driver.h.
|
protected |
Counts number of out-of-order (or duplicate) received packets.
Definition at line 95 of file netft_rdt_driver.h.
|
protected |
Count number of received <good> packets.
Definition at line 91 of file netft_rdt_driver.h.
|
protected |
Definition at line 80 of file netft_rdt_driver.h.
|
protected |
Set if recv thread exited because of error.
Definition at line 86 of file netft_rdt_driver.h.
|
protected |
True if recv loop is still running.
Definition at line 84 of file netft_rdt_driver.h.
|
protected |
Incremental counter for wrench header.
Definition at line 97 of file netft_rdt_driver.h.
|
protected |
Definition at line 78 of file netft_rdt_driver.h.
|
protected |
Definition at line 82 of file netft_rdt_driver.h.
|
protected |
to keep track of any error codes reported by netft
Definition at line 112 of file netft_rdt_driver.h.
|
protected |
Scaling factor for converting raw torque values into Newton*meters.
Definition at line 102 of file netft_rdt_driver.h.