39 using boost::asio::ip::udp;
57 void unpack(
const uint8_t *buffer);
58 static uint32_t
unpack32(
const uint8_t *buffer);
64 ( uint32_t(buffer[0]) << 24) |
65 ( uint32_t(buffer[1]) << 16) |
66 ( uint32_t(buffer[2]) << 8 ) |
67 ( uint32_t(buffer[3]) << 0 ) ;
100 CMD_START_HIGH_SPEED_STREAMING=2,
105 enum { INFINITE_SAMPLES=0 };
107 enum {RDT_COMMAND_SIZE = 8};
111 void pack(uint8_t *buffer)
const;
117 buffer[0] = (command_header_ >> 8) & 0xFF;
118 buffer[1] = (command_header_ >> 0) & 0xFF;
119 buffer[2] = (command_ >> 8) & 0xFF;
120 buffer[3] = (command_ >> 0) & 0xFF;
121 buffer[4] = (sample_count_ >> 8) & 0xFF;
122 buffer[5] = (sample_count_ >> 0) & 0xFF;
123 buffer[6] = (sample_count_ >> 8) & 0xFF;
124 buffer[7] = (sample_count_ >> 0) & 0xFF;
130 socket_(io_service_),
131 stop_recv_thread_(false),
132 recv_thread_running_(false),
135 out_of_order_count_(0),
137 diag_packet_count_(0),
138 last_diag_pub_time_(
ros::Time::now()),
139 last_rdt_sequence_(0),
143 udp::endpoint netft_endpoint( boost::asio::ip::address_v4::from_string(address),
RDT_PORT);
145 socket_.connect(netft_endpoint);
151 static const double counts_per_force = 1000000;
152 static const double counts_per_torque = 1000000;
161 for (
int i=0; i<10; ++i)
167 { boost::unique_lock<boost::mutex> lock(
mutex_);
170 throw std::runtime_error(
"No data received from NetFT device");
182 if (!
recv_thread_.timed_join(boost::posix_time::time_duration(0,0,1,0)))
184 ROS_WARN(
"Interrupting recv thread");
186 if (!
recv_thread_.timed_join(boost::posix_time::time_duration(0,0,1,0)))
188 ROS_WARN(
"Failed second join to recv thread");
198 bool got_new_data =
false;
200 boost::mutex::scoped_lock lock(
mutex_);
202 condition_.timed_wait(lock, boost::posix_time::milliseconds(100));
218 start_transmission.
pack(buffer);
229 geometry_msgs::WrenchStamped tmp_data;
236 ROS_WARN(
"Receive size of %d bytes does not match expected size of %d",
241 rdt_record.
unpack(buffer);
245 boost::unique_lock<boost::mutex> lock(
mutex_);
251 { boost::unique_lock<boost::mutex> lock(
mutex_);
259 tmp_data.header.frame_id =
"base_link";
266 { boost::unique_lock<boost::mutex> lock(
mutex_);
276 catch (std::exception &e)
279 { boost::unique_lock<boost::mutex> lock(
mutex_);
288 { boost::unique_lock<boost::mutex> lock(
mutex_);
297 d.name =
"NetFT RDT Driver : " +
address_;
326 d.
addf(
"Recv rate (pkt/sec)",
"%.2f", recv_rate);
330 geometry_msgs::WrenchStamped
data;
332 d.
addf(
"Force X (N)",
"%f", data.wrench.force.x);
333 d.
addf(
"Force Y (N)",
"%f", data.wrench.force.y);
334 d.
addf(
"Force Z (N)",
"%f", data.wrench.force.z);
335 d.
addf(
"Torque X (Nm)",
"%f", data.wrench.torque.x);
336 d.
addf(
"Torque Y (Nm)",
"%f", data.wrench.torque.y);
337 d.
addf(
"Torque Z (Nm)",
"%f", data.wrench.torque.z);
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.
void summary(unsigned char lvl, const std::string s)
void unpack(const uint8_t *buffer)
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_
void pack(uint8_t *buffer) const
Packet structure into buffer for network transport.
void addf(const std::string &key, const char *format,...)
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_
void mergeSummary(unsigned char lvl, const std::string s)
static uint32_t unpack32(const uint8_t *buffer)
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.
void mergeSummaryf(unsigned char lvl, const char *format,...)
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.