netft_rdt_driver.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef NETFT_RDT_DRIVER
36 #define NETFT_RDT_DRIVER
37 
38 #include <boost/asio.hpp>
39 #include <boost/thread/mutex.hpp>
40 #include <boost/thread/thread.hpp>
41 #include <boost/thread/condition.hpp>
42 #include <string>
43 
45 #include "geometry_msgs/WrenchStamped.h"
46 
48 {
49 
51 {
52 public:
53  // Start receiving data from NetFT device
54  NetFTRDTDriver(const std::string &address);
55 
57 
59  void getData(geometry_msgs::WrenchStamped &data);
60 
63 
65  // Returns true if new data has arrived, false it function times out
66  bool waitForNewData(void);
67 
68 protected:
69  void recvThreadFunc(void);
70 
72  void startStreaming(void);
73 
74  enum {RDT_PORT=49152};
75  std::string address_;
76 
77  boost::asio::io_service io_service_;
78  boost::asio::ip::udp::socket socket_;
79  boost::mutex mutex_;
80  boost::thread recv_thread_;
81  boost::condition condition_;
82  volatile bool stop_recv_thread_;
86  std::string recv_thread_error_msg_;
87 
89  geometry_msgs::WrenchStamped new_data_;
91  unsigned packet_count_;
93  unsigned lost_packets_;
97  unsigned seq_counter_;
98 
100  double force_scale_;
103 
108 
112  uint32_t system_status_;
113 };
114 
115 
116 } // end namespace netft_rdt_driver
117 
118 
119 #endif // NETFT_RDT_DRIVER
d
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.
data
unsigned packet_count_
Count number of received <good> packets.
boost::asio::io_service io_service_
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.
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Add device diagnostics status wrapper.
NetFTRDTDriver(const std::string &address)
unsigned seq_counter_
Incremental counter for wrench header.
double torque_scale_
Scaling factor for converting raw torque values into Newton*meters.


netft_utils
Author(s): Alex von Sternberg , Derek King, Andy Zelenak
autogenerated on Tue Mar 2 2021 03:15:08