35 #ifndef NETFT_RDT_DRIVER 36 #define NETFT_RDT_DRIVER 38 #include <boost/asio.hpp> 39 #include <boost/thread/mutex.hpp> 40 #include <boost/thread/thread.hpp> 41 #include <boost/thread/condition.hpp> 45 #include "geometry_msgs/WrenchStamped.h" 119 #endif // NETFT_RDT_DRIVER
unsigned out_of_order_count_
Counts number of out-of-order (or duplicate) received packets.
void getData(geometry_msgs::WrenchStamped &data)
Get newest RDT data from netFT device.
uint32_t system_status_
to keep track of any error codes reported by netft
double force_scale_
Scaling factor for converting raw force values from device into Newtons.
bool recv_thread_running_
True if recv loop is still running.
void startStreaming(void)
Asks NetFT to start streaming data.
unsigned packet_count_
Count number of received <good> packets.
volatile bool stop_recv_thread_
boost::asio::io_service io_service_
void recvThreadFunc(void)
geometry_msgs::WrenchStamped new_data_
Newest data received from netft device.
bool waitForNewData(void)
Wait for new NetFT data to arrive.
std::string recv_thread_error_msg_
Set if recv thread exited because of error.
unsigned lost_packets_
Count of lost RDT packets using RDT sequence number.
ros::Time last_diag_pub_time_
Last time diagnostics was published.
boost::asio::ip::udp::socket socket_
uint32_t last_rdt_sequence_
to keep track of out-of-order or duplicate packet
unsigned diag_packet_count_
Packet count last time diagnostics thread published output.
boost::thread recv_thread_
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Add device diagnostics status wrapper.
NetFTRDTDriver(const std::string &address)
boost::condition condition_
unsigned seq_counter_
Incremental counter for wrench header.
double torque_scale_
Scaling factor for converting raw torque values into Newton*meters.