6#define _USE_MATH_DEFINES
49 if (!config.
check(
"node_name"))
54 nodeName = config.
find(
"node_name").asString();
55 if(nodeName[0] !=
'/'){
62 if (!config.
check(
"topic_name"))
67 topicName = config.
find(
"topic_name").asString();
68 if(topicName[0] !=
'/'){
75 if (!config.
check(
"frame_id"))
80 frame_id = config.
find(
"frame_id").asString();
86bool Rangefinder2D_nws_ros::initialize_ROS()
94 if (!publisherPort.
topic(topicName))
110 driver->
view(sens_p);
113 if (
nullptr == sens_p)
167 if (!config.
check(
"period"))
172 _period = config.
find(
"period").asFloat64();
174 checkROSParams(config);
177 if (!initialize_ROS())
188 publisherPort.
close();
216 yarp::rosmsg::sensor_msgs::LaserScan &
rosData = publisherPort.
prepare();
217 rosData.header.seq = msgCounter++;
219 rosData.header.frame_id = frame_id;
223 rosData.angle_increment = resolution *
M_PI / 180.0;
226 rosData.range_min = minDistance;
227 rosData.range_max = maxDistance;
235 if (std::isnan(
ranges[i]))
237 rosData.ranges[i] = std::numeric_limits<double>::infinity();
246 publisherPort.
write();
define control board standard interfaces
const yarp::os::LogComponent & RANGEFINDER2D_NWS_ROS()
rangefinder2D_nws_ros: A Network grabber for 2D Rangefinder devices. This device will publish data on...
bool close() override
Close the DeviceDriver.
void threadRelease() override
Release method.
bool detach() override
Detach the object (you must have first called attach).
bool open(yarp::os::Searchable ¶ms) override
Open the DeviceDriver.
void attach(yarp::dev::IRangefinder2D *s)
bool threadInit() override
Initialization method.
void run() override
Loop function.
bool view(T *&x)
Get an interface to the device driver.
A generic interface for planar laser range finders.
virtual ReturnValue getRawData(yarp::sig::Vector &data, double *timestamp=nullptr)=0
Get the device measurements.
virtual ReturnValue getDistanceRange(double &min, double &max)=0
get the device detection range
virtual ReturnValue getScanLimits(double &min, double &max)=0
get the scan angular range.
virtual ReturnValue getHorizontalResolution(double &step)=0
get the angular step between two measurements.
virtual ReturnValue getDeviceStatus(Device_status &status)=0
get the device status
A container for a device driver.
bool isValid() const
Check if device is valid.
A mini-server for performing network communication in the background.
void interrupt()
interrupt delegates the call to the Node port interrupt.
An abstraction for a periodic thread.
bool setPeriod(double period)
Set the (new) period of the thread.
bool isRunning() const
Returns true when the thread is started, false otherwise.
bool start()
Call this to start the thread.
double getPeriod() const
Return the current period of 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 close() override
Stop port activity.
bool topic(const std::string &name)
Set topic to publish to.
void write(bool forceStrict=false)
Write the current object being returned by Publisher::prepare.
T & prepare()
Access the object which will be transmitted by the next call to yarp::os::Publisher::write.
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.
void update()
Set the timestamp to the current time, and increment the sequence number (wrapping to 0 if the sequen...
double getTime() const
Get the time stamp.
#define yCInfo(component,...)
#define yCError(component,...)
#define yCTrace(component,...)
#define YARP_LOG_COMPONENT(name,...)
For streams capable of holding different kinds of content, check what they actually have.
double now()
Return the current time in seconds, relative to an arbitrary starting point.
An interface to the operating system, including Port based communication.