19 #define _USE_MATH_DEFINES
41 #define DEG2RAD M_PI/180.0
45 #define RAD2DEG 180/M_PI
89 m_contains_data=
false;
99 size_t ros_size = b.
ranges.size();
100 if (ros_size != m_lastScan.scans.size())
102 m_lastScan.scans.resize (ros_size);
104 for (
size_t i = 0; i < ros_size; i++)
106 m_lastScan.scans[i] = b.
ranges[i];
108 getEnvelope(m_lastStamp);
109 m_contains_data=
true;
110 m_port_mutex.unlock();
117 while (m_contains_data==
false)
120 if (counter++ > 100) {
yDebug() <<
"Waiting for incoming data..."; counter=0;}
126 m_port_mutex.unlock();
134 m_info =
"LaserFromRosTopic device";
140 if (this->parseConfiguration(config) ==
false)
148 if (general_config.
check(
"input_topics_name"))
153 for (
size_t i = 0; i < portlist->
size(); i++)
154 m_port_names.push_back(portlist->
get(i).
asString());
158 m_port_names.push_back(
"/laserFromExternalPort:i");
161 for (
size_t i = 0; i < m_port_names.size(); i++)
164 m_input_ports.push_back(proc);
166 m_last_stamp.resize(m_port_names.size());
167 m_last_scan_data.resize(m_port_names.size());
170 if (general_config.
check(
"base_type"))
172 string bt = general_config.
find(
"base_type").
asString();
181 m_empty_laser_data = m_laser_data;
184 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::numeric_limits<double>::infinity();
188 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::nanf(
"");
192 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = 0;
200 if (general_config.
check(
"override"))
202 if (m_input_ports.size() != 1)
209 m_option_override_limits =
true;
214 if (config.
check(
"TRANSFORMS") && config.
check(
"TRANSFORM_CLIENT"))
220 if (src_frames_list->
size() != m_input_ports.size())
225 for (
size_t i = 0; i < src_frames_list->
size(); i++)
227 m_src_frame_id.push_back(src_frames_list->
get(i).
asString());
235 m_dst_frame_id = transforms_config.
find(
"dst_frame").
asString();
236 if (m_dst_frame_id==
"")
244 if (client_cfg_string==
"")
252 tcprop.
put(
"device",
"transformClient");
254 m_tc_driver.open(tcprop);
255 if (!m_tc_driver.isValid())
260 m_tc_driver.view(m_iTc);
270 for (
size_t i = 0; i < m_input_ports.size(); i++)
273 if (m_input_ports[i].topic(m_port_names[i]) ==
false)
278 m_input_ports[i].useCallback();
280 PeriodicThread::start();
282 yInfo(
"LaserFromRosTopic: Sensor ready");
288 PeriodicThread::stop();
290 for (
auto it=m_input_ports.begin(); it!= m_input_ports.end(); it++)
294 if (m_ros_node) {
delete m_ros_node; m_ros_node =
nullptr; }
304 std::lock_guard<std::mutex> guard(m_mutex);
305 m_min_distance = min;
306 m_max_distance = max;
312 std::lock_guard<std::mutex> guard(m_mutex);
321 std::lock_guard<std::mutex> guard(m_mutex);
328 std::lock_guard<std::mutex> guard(m_mutex);
349 double t_off_rad = temp[2];
350 double x_off = m[0][3];
351 double y_off = m[1][3];
353 #ifdef DO_NOTHING_DEBUG
356 double t_off_deg = 0;
357 double t_off_rad = 0;
362 for (
size_t i = 0; i < scan_data.
scans.
size(); i++)
364 double distance = scan_data.
scans[i];
365 if (distance == std::numeric_limits<double>::infinity())
369 if (std::isnan(distance))
376 double angle_input_deg = (i * resolution) + scan_data.
angle_min;
377 double angle_input_rad = (angle_input_deg) *
DEG2RAD;
380 double Ay = (sin(angle_input_rad + t_off_rad) * distance);
381 double Ax = (cos(angle_input_rad + t_off_rad) * distance);
384 double By = Ay + y_off;
385 double Bx = Ax + x_off;
387 double angle_output_rad = atan2(By, Bx);
388 double angle_output_deg = angle_output_rad *
RAD2DEG;
392 if (angle_output_deg > m_max_angle) {
continue; }
393 if (angle_output_deg < m_min_angle) {
continue; }
396 int new_i = lrint ((angle_output_deg - m_min_angle) / m_resolution);
397 if (new_i ==
static_cast<int>(m_laser_data.size())) {new_i=0;}
400 yAssert (new_i <
static_cast<int>(m_laser_data.size()));
403 double newdistance = std::sqrt((Bx * Bx) + (By * By));
406 if (std::isnan(m_laser_data[new_i]))
408 m_laser_data[new_i] = newdistance;
410 else if (newdistance < m_laser_data[new_i])
412 m_laser_data[new_i] = newdistance;
423 std::lock_guard<std::mutex> guard(m_mutex);
424 m_laser_data = m_empty_laser_data;
426 size_t nports= m_input_ports.size();
429 m_input_ports[0].getLast(m_last_scan_data[0], m_last_stamp[0]);
430 size_t received_scans = m_last_scan_data[0].scans.size();
432 if (m_option_override_limits)
435 m_sensorsNum = received_scans;
436 m_max_angle = m_last_scan_data[0].angle_max;
437 m_min_angle = m_last_scan_data[0].angle_min;
438 m_max_distance = m_last_scan_data[0].range_max;
439 m_min_distance = m_last_scan_data[0].range_min;
440 m_resolution = received_scans / (m_max_angle - m_min_angle);
441 if (m_laser_data.size() != m_sensorsNum) m_laser_data.resize(m_sensorsNum);
446 for (
size_t elem = 0; elem < m_sensorsNum; elem++)
448 m_laser_data[elem] = m_last_scan_data[0].scans[elem];
454 bool frame_exists = m_iTc->getTransform(m_src_frame_id[0], m_dst_frame_id, m);
455 if (frame_exists ==
false)
459 calculate(m_last_scan_data[0], m);
464 for (
size_t i = 0; i < nports; i++)
467 bool frame_exists = m_iTc->getTransform(m_src_frame_id[i], m_dst_frame_id, m);
468 if (frame_exists ==
false)
472 m_input_ports[i].getLast(m_last_scan_data[i], m_last_stamp[i]);
473 calculate(m_last_scan_data[i], m);
477 applyLimitsOnLaserData();