6 #define _USE_MATH_DEFINES
27 #define DEG2RAD M_PI/180.0
31 #define RAD2DEG 180/M_PI
76 m_contains_data=
false;
86 size_t ros_size = b.
ranges.size();
87 if (ros_size != m_lastScan.scans.size())
89 m_lastScan.scans.resize (ros_size);
91 for (
size_t i = 0; i < ros_size; i++)
93 m_lastScan.scans[i] = b.
ranges[i];
95 getEnvelope(m_lastStamp);
97 m_port_mutex.unlock();
104 while (m_contains_data==
false)
107 if (counter++ > 100) {
yDebug() <<
"Waiting for incoming data..."; counter=0;}
113 m_port_mutex.unlock();
121 m_info =
"LaserFromRosTopic device";
127 if (this->parseConfiguration(config) ==
false)
135 if (general_config.
check(
"input_topics_name"))
140 for (
size_t i = 0; i < portlist->
size(); i++) {
141 m_port_names.push_back(portlist->
get(i).
asString());
146 m_port_names.push_back(
"/laserFromExternalPort:i");
149 for (
size_t i = 0; i < m_port_names.size(); i++)
152 m_input_ports.push_back(proc);
154 m_last_stamp.resize(m_port_names.size());
155 m_last_scan_data.resize(m_port_names.size());
158 if (general_config.
check(
"base_type"))
160 std::string bt = general_config.
find(
"base_type").
asString();
169 m_empty_laser_data = m_laser_data;
172 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) {
173 m_empty_laser_data[i] = std::numeric_limits<double>::infinity();
178 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) {
179 m_empty_laser_data[i] = std::nanf(
"");
184 for (
size_t i = 0; i < m_empty_laser_data.size(); i++) {
185 m_empty_laser_data[i] = 0;
194 if (general_config.
check(
"override"))
196 if (m_input_ports.size() != 1)
203 m_option_override_limits =
true;
208 if (config.
check(
"TRANSFORMS") && config.
check(
"TRANSFORM_CLIENT"))
214 if (src_frames_list->
size() != m_input_ports.size())
219 for (
size_t i = 0; i < src_frames_list->
size(); i++)
221 m_src_frame_id.push_back(src_frames_list->
get(i).
asString());
229 m_dst_frame_id = transforms_config.
find(
"dst_frame").
asString();
230 if (m_dst_frame_id==
"")
238 if (client_cfg_string==
"")
246 tcprop.
put(
"device",
"transformClient");
248 m_tc_driver.open(tcprop);
249 if (!m_tc_driver.isValid())
254 m_tc_driver.view(m_iTc);
264 for (
size_t i = 0; i < m_input_ports.size(); i++)
267 if (m_input_ports[i].topic(m_port_names[i]) ==
false)
272 m_input_ports[i].useCallback();
276 yInfo(
"LaserFromRosTopic: Sensor ready");
284 for (
auto it=m_input_ports.begin(); it!= m_input_ports.end(); it++)
288 if (m_ros_node) {
delete m_ros_node; m_ros_node =
nullptr; }
298 std::lock_guard<std::mutex> guard(m_mutex);
299 m_min_distance = min;
300 m_max_distance = max;
306 std::lock_guard<std::mutex> guard(m_mutex);
315 std::lock_guard<std::mutex> guard(m_mutex);
322 std::lock_guard<std::mutex> guard(m_mutex);
343 double t_off_rad = temp[2];
344 double x_off = m[0][3];
345 double y_off = m[1][3];
347 #ifdef DO_NOTHING_DEBUG
350 double t_off_deg = 0;
351 double t_off_rad = 0;
356 for (
size_t i = 0; i < scan_data.
scans.
size(); i++)
358 double distance = scan_data.
scans[i];
359 if (distance == std::numeric_limits<double>::infinity())
363 if (std::isnan(distance))
370 double angle_input_deg = (i * resolution) + scan_data.
angle_min;
371 double angle_input_rad = (angle_input_deg) *
DEG2RAD;
374 double Ay = (sin(angle_input_rad + t_off_rad) * distance);
375 double Ax = (cos(angle_input_rad + t_off_rad) * distance);
378 double By = Ay + y_off;
379 double Bx = Ax + x_off;
381 double angle_output_rad = atan2(By, Bx);
382 double angle_output_deg = angle_output_rad *
RAD2DEG;
386 if (angle_output_deg > m_max_angle) {
continue; }
387 if (angle_output_deg < m_min_angle) {
continue; }
390 int new_i = lrint ((angle_output_deg - m_min_angle) / m_resolution);
391 if (new_i ==
static_cast<int>(m_laser_data.size())) {new_i=0;}
394 yAssert (new_i <
static_cast<int>(m_laser_data.size()));
397 double newdistance = std::sqrt((Bx * Bx) + (By * By));
400 if (std::isnan(m_laser_data[new_i]))
402 m_laser_data[new_i] = newdistance;
404 else if (newdistance < m_laser_data[new_i])
406 m_laser_data[new_i] = newdistance;
417 std::lock_guard<std::mutex> guard(m_mutex);
418 m_laser_data = m_empty_laser_data;
420 size_t nports = m_input_ports.size();
423 m_input_ports[0].getLast(m_last_scan_data[0], m_last_stamp[0]);
424 size_t received_scans = m_last_scan_data[0].scans.size();
426 if (m_option_override_limits)
429 m_sensorsNum = received_scans;
430 m_max_angle = m_last_scan_data[0].angle_max;
431 m_min_angle = m_last_scan_data[0].angle_min;
432 m_max_distance = m_last_scan_data[0].range_max;
433 m_min_distance = m_last_scan_data[0].range_min;
434 m_resolution = received_scans / (m_max_angle - m_min_angle);
435 if (m_laser_data.size() != m_sensorsNum) {
436 m_laser_data.resize(m_sensorsNum);
440 if (m_iTc ==
nullptr)
442 for (
size_t elem = 0; elem < m_sensorsNum; elem++)
444 m_laser_data[elem] = m_last_scan_data[0].scans[elem];
450 bool frame_exists = m_iTc->getTransform(m_src_frame_id[0], m_dst_frame_id, m);
451 if (frame_exists ==
false)
455 calculate(m_last_scan_data[0], m);
460 for (
size_t i = 0; i < nports; i++)
463 bool frame_exists = m_iTc->getTransform(m_src_frame_id[i], m_dst_frame_id, m);
464 if (frame_exists ==
false)
468 m_input_ports[i].getLast(m_last_scan_data[i], m_last_stamp[i]);
469 calculate(m_last_scan_data[i], m);
double constrainAngle(double x)
const yarp::os::LogComponent & LASER_FROM_ROS_TOPIC()
bool close() override
Close the DeviceDriver.
bool setDistanceRange(double min, double max) override
set the device detection range.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
void calculate(yarp::dev::LaserScan2D scan, yarp::sig::Matrix m)
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
void run() override
Loop function.
bool setScanLimits(double min, double max) override
set the scan angular range.
bool threadInit() override
Initialization method.
bool acquireDataFromHW() override final
This method should be implemented by the user, and contain the logic to grab data from the hardware.
void threadRelease() override
Release method.
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
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.
bool start()
Call this to start the thread.
void stop()
Call this to stop the thread, this call blocks until the thread is terminated (and releaseThread() ca...
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.
yarp::conf::float32_t range_min
yarp::conf::float32_t angle_min
std::vector< yarp::conf::float32_t > ranges
yarp::conf::float32_t range_max
yarp::conf::float32_t angle_max
const Matrix & eye()
Build an identity matrix, don't resize.
#define yCInfo(component,...)
#define yCError(component,...)
#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.