19 #define _USE_MATH_DEFINES
41 #define DEG2RAD M_PI/180.0
45 #define RAD2DEG 180/M_PI
83 m_contains_data=
false;
90 getEnvelope(m_lastStamp);
92 m_port_mutex.unlock();
99 while (m_contains_data==
false)
108 m_port_mutex.unlock();
116 m_info =
"LaserFromExternalPort device";
122 if (this->parseConfiguration(config) ==
false)
130 if (general_config.
check(
"input_ports_name"))
135 for (
size_t i = 0; i < portlist->
size(); i++)
136 m_port_names.push_back(portlist->
get(i).
asString());
140 m_port_names.push_back(
"/laserFromExternalPort:i");
143 for (
size_t i = 0; i < m_port_names.size(); i++)
146 m_input_ports.push_back(proc);
148 m_last_stamp.resize(m_port_names.size());
149 m_last_scan_data.resize(m_port_names.size());
152 if (general_config.
check(
"base_type"))
154 string bt = general_config.
find(
"base_type").
asString();
163 m_empty_laser_data = m_laser_data;
166 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::numeric_limits<double>::infinity();
170 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = std::nanf(
"");
174 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) m_empty_laser_data[i] = 0;
182 if (general_config.
check(
"override"))
184 if (m_input_ports.size() != 1)
191 m_option_override_limits =
true;
196 if (config.
check(
"TRANSFORMS") && config.
check(
"TRANSFORM_CLIENT"))
202 if (src_frames_list->
size() != m_input_ports.size())
207 for (
size_t i = 0; i < src_frames_list->
size(); i++)
209 m_src_frame_id.push_back(src_frames_list->
get(i).
asString());
217 m_dst_frame_id = transforms_config.
find(
"dst_frame").
asString();
218 if (m_dst_frame_id==
"")
226 if (client_cfg_string==
"")
234 tcprop.
put(
"device",
"transformClient");
236 m_tc_driver.open(tcprop);
237 if (!m_tc_driver.isValid())
242 m_tc_driver.view(m_iTc);
251 for (
size_t i=0; i<m_input_ports.size(); i++)
253 m_input_ports[i].useCallback();
254 if (m_input_ports[i].open(m_port_names[i]) ==
false)
260 PeriodicThread::start();
268 PeriodicThread::stop();
270 for (
auto it=m_input_ports.begin(); it!= m_input_ports.end(); it++)
283 std::lock_guard<std::mutex> guard(m_mutex);
284 m_min_distance = min;
285 m_max_distance = max;
291 std::lock_guard<std::mutex> guard(m_mutex);
300 std::lock_guard<std::mutex> guard(m_mutex);
307 std::lock_guard<std::mutex> guard(m_mutex);
328 double t_off_rad = temp[2];
329 double x_off = m[0][3];
330 double y_off = m[1][3];
332 #ifdef DO_NOTHING_DEBUG
335 double t_off_deg = 0;
336 double t_off_rad = 0;
341 for (
size_t i = 0; i < scan_data.
scans.
size(); i++)
343 double distance = scan_data.
scans[i];
344 if (distance == std::numeric_limits<double>::infinity())
348 if (std::isnan(distance))
355 double angle_input_deg = (i * resolution) + scan_data.
angle_min;
356 double angle_input_rad = (angle_input_deg) *
DEG2RAD;
359 double Ay = (sin(angle_input_rad + t_off_rad) * distance);
360 double Ax = (cos(angle_input_rad + t_off_rad) * distance);
363 double By = Ay + y_off;
364 double Bx = Ax + x_off;
366 double angle_output_rad = atan2(By, Bx);
367 double angle_output_deg = angle_output_rad *
RAD2DEG;
371 if (angle_output_deg > m_max_angle) {
continue; }
372 if (angle_output_deg < m_min_angle) {
continue; }
375 int new_i = lrint ((angle_output_deg - m_min_angle) / m_resolution);
376 if (
static_cast<size_t>(new_i) == m_laser_data.size()) {new_i=0;}
382 double newdistance = std::sqrt((Bx * Bx) + (By * By));
385 if (std::isnan(m_laser_data[new_i]))
387 m_laser_data[new_i] = newdistance;
389 else if (newdistance < m_laser_data[new_i])
391 m_laser_data[new_i] = newdistance;
402 std::lock_guard<std::mutex> guard(m_mutex);
403 m_laser_data = m_empty_laser_data;
405 size_t nports= m_input_ports.size();
408 m_input_ports[0].getLast(m_last_scan_data[0], m_last_stamp[0]);
409 size_t received_scans = m_last_scan_data[0].scans.size();
411 if (m_option_override_limits)
414 m_sensorsNum = received_scans;
415 m_max_angle = m_last_scan_data[0].angle_max;
416 m_min_angle = m_last_scan_data[0].angle_min;
417 m_max_distance = m_last_scan_data[0].range_max;
418 m_min_distance = m_last_scan_data[0].range_min;
419 m_resolution = received_scans / (m_max_angle - m_min_angle);
420 if (m_laser_data.size() != m_sensorsNum) m_laser_data.resize(m_sensorsNum);
425 for (
size_t elem = 0; elem < m_sensorsNum; elem++)
427 m_laser_data[elem] = m_last_scan_data[0].scans[elem];
433 bool frame_exists = m_iTc->getTransform(m_src_frame_id[0], m_dst_frame_id, m);
434 if (frame_exists ==
false)
438 calculate(m_last_scan_data[0], m);
443 for (
size_t i=0; i<nports;i++)
446 bool frame_exists = m_iTc->getTransform(m_src_frame_id[i], m_dst_frame_id, m);
447 if (frame_exists ==
false)
451 m_input_ports[i].getLast(m_last_scan_data[i], m_last_stamp[i]);
452 calculate(m_last_scan_data[i], m);
456 applyLimitsOnLaserData();
bool close() override
Close the DeviceDriver.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
bool threadInit() override
Initialization method.
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
void calculate(yarp::dev::LaserScan2D scan, yarp::sig::Matrix m)
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
bool setDistanceRange(double min, double max) override
set the device detection range.
void run() override
Loop function.
void threadRelease() override
Release method.
bool setScanLimits(double min, double max) override
set the scan angular range.
yarp::sig::Vector scans
the scan data, measured in [m].
double angle_min
first angle of the scan [deg]
double angle_max
last angle of the scan [deg]
A simple collection of objects that can be described and transmitted in a portable way.
size_type size() const
Gets the number of elements in the bottle.
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
std::string toString() const override
Gives a human-readable textual representation of the bottle.
A class for storing options and configuration information.
void fromString(const std::string &txt, bool wipe=true)
Interprets a string as a list of properties.
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
A base class for nested structures that can be searched.
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
An abstraction for a time stamp and/or sequence number.
virtual Bottle * asList() const
Get list value.
virtual std::string asString() const
Get string value.
const Matrix & eye()
Build an identity matrix, don't resize.
double constrainAngle(double x)
const yarp::os::LogComponent & LASER_FROM_EXTERNAL_PORT()
#define yCInfo(component,...)
#define yCError(component,...)
#define yCAssert(component, x)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
An interface for the device drivers.
yarp::sig::Vector dcm2rpy(const yarp::sig::Matrix &R)
Converts a dcm (direction cosine matrix) rotation matrix to roll-pitch-yaw angles (defined in Math....
double now()
Return the current time in seconds, relative to an arbitrary starting point.
void delay(double seconds)
Wait for a certain number of seconds.
An interface to the operating system, including Port based communication.