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();
91 for (
size_t i = 0; i < ros_size; i++)
93 m_lastScan.
scans[i] = b.ranges[i];
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";
135 if (general_config.
check(
"input_topics_name"))
140 for (
size_t i = 0; i < portlist->
size(); i++) {
158 if (general_config.
check(
"base_type"))
160 std::string bt = general_config.
find(
"base_type").
asString();
194 if (general_config.
check(
"override"))
208 if (config.
check(
"TRANSFORMS") && config.
check(
"TRANSFORM_CLIENT"))
219 for (
size_t i = 0; i < src_frames_list->
size(); i++)
238 if (client_cfg_string==
"")
246 tcprop.
put(
"device",
"transformClient");
274 PeriodicThread::start();
276 yInfo(
"LaserFromRosTopic: Sensor ready");
282 PeriodicThread::stop();
298 std::lock_guard<std::mutex> guard(
m_mutex);
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;
397 double newdistance = std::sqrt((Bx * Bx) + (By * By));
417 std::lock_guard<std::mutex> guard(
m_mutex);
440 if (
m_iTc ==
nullptr)
451 if (frame_exists ==
false)
460 for (
size_t i = 0; i < nports; i++)
464 if (frame_exists ==
false)
double constrainAngle(double x)
const yarp::os::LogComponent & LASER_FROM_ROS_TOPIC()
std::vector< yarp::dev::LaserScan2D > m_last_scan_data
bool close() override
Close the DeviceDriver.
std::vector< InputPortProcessor > m_input_ports
bool setDistanceRange(double min, double max) override
set the device detection range.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
std::vector< yarp::os::Stamp > m_last_stamp
void calculate(yarp::dev::LaserScan2D scan, yarp::sig::Matrix m)
std::vector< std::string > m_port_names
bool setHorizontalResolution(double step) override
get the angular step between two measurements (if available)
void run() override
Loop function.
yarp::os::Node * m_ros_node
yarp::dev::PolyDriver m_tc_driver
bool setScanLimits(double min, double max) override
set the scan angular range.
bool threadInit() override
Initialization method.
yarp::sig::Vector m_empty_laser_data
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.
std::vector< std::string > m_src_frame_id
yarp::dev::IFrameTransform * m_iTc
std::string m_dst_frame_id
bool m_option_override_limits
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
bool view(T *&x)
Get an interface to the device driver.
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]
double range_min
the minimum distance of the scan [m]
double range_max
the maximum distance of the scan [m]
virtual bool updateLidarData()
This utility method calls in sequence: grabDataFromHW(), updateTimestamp and applyLimitsOnLaserData()...
bool parseConfiguration(yarp::os::Searchable &config)
yarp::sig::Vector m_laser_data
bool isValid() const
Check if device is valid.
bool open(const std::string &txt)
Construct and configure a device by its common name.
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 getEnvelope(PortReader &envelope) override
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 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 Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
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.
void resize(size_t size) override
Resize the vector.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCWarning(component,...)
#define yCDebug(component,...)
#define YARP_LOG_COMPONENT(name,...)
yarp::rosmsg::sensor_msgs::LaserScan LaserScan
For streams capable of holding different kinds of content, check what they actually have.
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.