pf_interface.cpp
Go to the documentation of this file.
1 #include <algorithm>
2 #include <memory>
3 #include <string>
4 #include <utility>
5 
11 
12 PFInterface::PFInterface() : state_(PFState::UNINIT)
13 {
14 }
15 
16 bool PFInterface::init(std::shared_ptr<HandleInfo> info, std::shared_ptr<ScanConfig> config,
17  std::shared_ptr<ScanParameters> params, const std::string& topic, const std::string& frame_id,
18  const uint16_t num_layers)
19 {
20  config_ = config;
21  info_ = info;
22  params_ = params;
23 
24  topic_ = topic;
25  frame_id_ = frame_id;
26  num_layers_ = num_layers;
27 
28  protocol_interface_ = std::make_shared<PFSDPBase>(info, config, params);
29  // This is the first time ROS communicates with the device
30  auto opi = protocol_interface_->get_protocol_info();
31  if (opi.isError)
32  {
33  ROS_ERROR("Unable to communicate with device. Please check the IP address");
34  return false;
35  }
36 
37  if (opi.protocol_name != "pfsdp")
38  {
39  ROS_ERROR("Incorrect protocol");
40  return false;
41  }
42 
43  if (!handle_version(opi.version_major, opi.version_minor, opi.device_family, topic, frame_id, num_layers))
44  {
45  ROS_ERROR("Device unsupported");
46  return false;
47  }
48  ROS_INFO("Device found: %s", product_.c_str());
49 
50  // release previous handles
51  if (!prev_handle_.empty())
52  {
53  protocol_interface_->release_handle(prev_handle_);
54  }
55 
56  if (info->handle_type == HandleInfo::HANDLE_TYPE_UDP)
57  {
58  transport_ = std::make_unique<UDPTransport>(info->hostname, info->port);
59  if (!transport_->connect())
60  {
61  ROS_ERROR("Unable to establish UDP connection");
62  return false;
63  }
64 
65  info_->endpoint = transport_->get_host_ip();
66  info_->port = transport_->get_port();
67  protocol_interface_->request_handle_udp();
68  }
69  else if (info->handle_type == HandleInfo::HANDLE_TYPE_TCP)
70  {
71  transport_ = std::make_unique<TCPTransport>(info->hostname);
72  protocol_interface_->request_handle_tcp();
73  // if initially port was not set, request_handle sets it
74  // set the updated port in transport
75  transport_->set_port(info_->port);
76  if (!transport_->connect())
77  {
78  ROS_ERROR("Unable to establish TCP connection");
79  return false;
80  }
81  }
82  else
83  {
84  ROS_ERROR("Incorrect transport option");
85  return false;
86  }
87 
88  if (info_->handle.empty())
89  {
90  ROS_ERROR("Could not acquire communication handle");
91  return false;
92  }
93 
94  prev_handle_ = info_->handle;
95 
96  protocol_interface_->setup_param_server();
97  protocol_interface_->set_connection_failure_cb(std::bind(&PFInterface::connection_failure_cb, this));
98  // protocol_interface_->update_scanoutput_config();
100  return true;
101 }
102 
104 {
105  if (state_ == state)
106  return;
107  state_ = state; // Can use this function later
108  // to check state transitions
109  std::string text;
110  if (state_ == PFState::UNINIT)
111  text = "Uninitialized";
112  if (state_ == PFState::INIT)
113  text = "Initialized";
114  if (state_ == PFState::RUNNING)
115  text = "Running";
116  if (state_ == PFState::SHUTDOWN)
117  text = "Shutdown";
118  if (state_ == PFState::ERROR)
119  text = "Error";
120  ROS_INFO("Device state changed to %s", text.c_str());
121 }
122 
124 {
125  return true;
126 }
127 
128 bool PFInterface::start_transmission(std::shared_ptr<std::mutex> net_mtx,
129  std::shared_ptr<std::condition_variable> net_cv, bool& net_fail)
130 {
131  if (state_ != PFState::INIT)
132  return false;
133 
134  if (pipeline_ && pipeline_->is_running())
135  return true;
136 
137  pipeline_ = get_pipeline(config_->packet_type, net_mtx, net_cv, net_fail);
138  if (!pipeline_ || !pipeline_->start())
139  return false;
140 
141  protocol_interface_->start_scanoutput();
142  if (config_->watchdog)
143  start_watchdog_timer(config_->watchdogtimeout / 1000.0);
144 
146  return true;
147 }
148 
149 // What happens to the connection_ obj?
151 {
152  if (state_ != PFState::RUNNING)
153  return;
154  protocol_interface_->stop_scanoutput(info_->handle);
155  protocol_interface_->release_handle(info_->handle);
157 }
158 
160 {
161  if (!pipeline_)
162  return;
164  pipeline_->terminate();
165  pipeline_.reset();
166  protocol_interface_.reset();
167  transport_.reset();
169 }
170 
172 {
174 }
175 
177 {
178  // dividing the watchdogtimeout by 2 to have a “safe” feed time within the defined timeout
179  float feed_time = std::min(duration, 60.0f) / 2.0f;
181  nh_.createTimer(ros::Duration(feed_time), std::bind(&PFInterface::feed_watchdog, this, std::placeholders::_1));
182 }
183 
185 {
186  protocol_interface_->feed_watchdog(info_->handle);
187 }
188 
190 {
191  ROS_INFO("Shutting down pipeline!");
192  // stop_transmission();
193 }
194 
196 {
197  std::cout << "handling connection failure" << std::endl;
198  terminate();
199  std::cout << "terminated" << std::endl;
200  while (!init())
201  {
202  std::cout << "trying to reconnect..." << std::endl;
203  std::this_thread::sleep_for(std::chrono::milliseconds(500));
204  }
205 }
206 
207 // factory functions
208 bool PFInterface::handle_version(int major_version, int minor_version, int device_family, const std::string& topic,
209  const std::string& frame_id, const uint16_t num_layers)
210 {
211  std::string expected_dev = "";
212  if (device_family == 1 || device_family == 3 || device_family == 6)
213  {
214  expected_dev = "R2000";
215  protocol_interface_ = std::make_shared<PFSDP_2000>(info_, config_, params_);
216  reader_ =
217  std::shared_ptr<PFPacketReader>(new LaserscanPublisher(config_, params_, topic.c_str(), frame_id.c_str()));
218  }
219  else if (device_family == 5 || device_family == 7)
220  {
221  expected_dev = "R2300";
222  protocol_interface_ = std::make_shared<PFSDP_2300>(info_, config_, params_);
223 
224  if (device_family == 5)
225  {
226  std::string part = protocol_interface_->get_part();
227  reader_ = std::shared_ptr<PFPacketReader>(
228  new PointcloudPublisher(config_, params_, topic.c_str(), frame_id.c_str(), num_layers, part.c_str()));
229  }
230  else if (device_family == 7)
231  {
232  reader_ =
233  std::shared_ptr<PFPacketReader>(new LaserscanPublisher(config_, params_, topic.c_str(), frame_id.c_str()));
234  }
235  else
236  {
237  return false;
238  }
239  }
240  else
241  {
242  return false;
243  }
244  std::string product_name = protocol_interface_->get_product();
245  if (product_name.find(expected_dev) != std::string::npos)
246  {
247  product_ = expected_dev;
248  return true;
249  }
250  return false;
251 }
252 
253 std::unique_ptr<Pipeline> PFInterface::get_pipeline(const std::string& packet_type, std::shared_ptr<std::mutex> net_mtx,
254  std::shared_ptr<std::condition_variable> net_cv, bool& net_fail)
255 {
256  std::shared_ptr<Parser<PFPacket>> parser;
257  std::shared_ptr<Writer<PFPacket>> writer;
258  if (product_ == "R2000")
259  {
260  ROS_DEBUG("PacketType is: %s", packet_type.c_str());
261  if (packet_type == "A")
262  {
263  parser = std::unique_ptr<Parser<PFPacket>>(new PFR2000_A_Parser);
264  }
265  else if (packet_type == "B")
266  {
267  parser = std::unique_ptr<Parser<PFPacket>>(new PFR2000_B_Parser);
268  }
269  else if (packet_type == "C")
270  {
271  parser = std::unique_ptr<Parser<PFPacket>>(new PFR2000_C_Parser);
272  }
273  }
274  else if (product_ == "R2300")
275  {
276  if (packet_type == "C1")
277  {
278  parser = std::unique_ptr<Parser<PFPacket>>(new PFR2300_C1_Parser);
279  }
280  }
281  if (!parser)
282  {
283  return nullptr;
284  }
285  writer = std::shared_ptr<Writer<PFPacket>>(new PFWriter<PFPacket>(std::move(transport_), parser));
286  return std::make_unique<Pipeline>(writer, reader_, std::bind(&PFInterface::connection_failure_cb, this), net_mtx,
287  net_cv, net_fail);
288 }
void start_watchdog_timer(float duration)
std::shared_ptr< Reader< PFPacket > > reader_
Definition: pf_interface.h:40
void change_state(PFState state)
f
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Timer watchdog_timer_
Definition: pf_interface.h:36
PFParser< PFR2000Packet_B > PFR2000_B_Parser
Definition: pf_parser.h:56
void stop()
uint16_t num_layers_
Definition: pf_interface.h:43
ros::NodeHandle nh_
Definition: pf_interface.h:35
#define ROS_ERROR(...)
std::string frame_id_
Definition: pf_interface.h:42
std::shared_ptr< ScanConfig > config_
Definition: pf_interface.h:47
#define ROS_DEBUG(...)
void terminate()
void feed_watchdog(const ros::TimerEvent &e)
PFParser< PFR2300Packet_C1 > PFR2300_C1_Parser
Definition: pf_parser.h:59
bool start_transmission(std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
void on_shutdown()
std::shared_ptr< ScanParameters > params_
Definition: pf_interface.h:48
#define ROS_INFO(...)
std::string prev_handle_
Definition: pf_interface.h:49
PFParser< PFR2000Packet_A > PFR2000_A_Parser
Definition: pf_parser.h:55
bool can_change_state(PFState state)
std::shared_ptr< HandleInfo > info_
Definition: pf_interface.h:46
PFState state_
Definition: pf_interface.h:59
PipelinePtr pipeline_
Definition: pf_interface.h:39
PFParser< PFR2000Packet_C > PFR2000_C_Parser
Definition: pf_parser.h:57
std::unique_ptr< Transport > transport_
Definition: pf_interface.h:37
parser
std::string topic_
Definition: pf_interface.h:41
PipelinePtr get_pipeline(const std::string &packet_type, std::shared_ptr< std::mutex > net_mtx, std::shared_ptr< std::condition_variable > net_cv, bool &net_fail)
static const int HANDLE_TYPE_TCP
Definition: handle_info.h:7
void connection_failure_cb()
bool handle_version(int major_version, int minor_version, int device_family, const std::string &topic, const std::string &frame_id, const uint16_t num_layers)
static const int HANDLE_TYPE_UDP
Definition: handle_info.h:8
void stop_transmission()
std::string product_
Definition: pf_interface.h:44
std::shared_ptr< PFSDPBase > protocol_interface_
Definition: pf_interface.h:38


pf_driver
Author(s): Harsh Deshpande
autogenerated on Fri Feb 24 2023 03:59:35