YARP
Yet Another Robot Platform
 
Loading...
Searching...
No Matches
Rangefinder2D_controlBoard_nws_ros2.h
Go to the documentation of this file.
1/*
2 * SPDX-FileCopyrightText: 2023 Istituto Italiano di Tecnologia (IIT)
3 * SPDX-License-Identifier: BSD-3-Clause
4 */
5
6#ifndef YARP_ROS2_RANGEFINDER2D_CONTROLBOARD_NWS_ROS2_H
7#define YARP_ROS2_RANGEFINDER2D_CONTROLBOARD_NWS_ROS2_H
8
13
17#include <yarp/dev/IAxisInfo.h>
18
19#include <rclcpp/rclcpp.hpp>
20#include <std_msgs/msg/string.hpp>
21
22#include <sensor_msgs/msg/laser_scan.hpp>
23#include <sensor_msgs/msg/joint_state.hpp>
24
26
27#include <mutex>
28
43{
44public:
51
52 //WrapperSingle
53 bool attach(yarp::dev::PolyDriver* driver) override;
54 bool detach() override;
55
56 // DeviceDriver
57 bool open(yarp::os::Searchable& config) override;
58 bool close() override;
59
60 bool setDevice(yarp::dev::DeviceDriver* device);
61 bool updateAxisName();
62
63 // PeriodicThread
64 void run() override;
65
66private:
67 yarp::dev::PolyDriver m_driver;
68 yarp::dev::DeviceDriver* m_driver_cb =nullptr;
69 yarp::dev::IRangefinder2D *m_iLidar =nullptr;
70 yarp::dev::IPositionControl* iPositionControl{nullptr};
71 yarp::dev::IEncodersTimed* iEncodersTimed{nullptr};
72 yarp::dev::ITorqueControl* iTorqueControl{nullptr};
73 yarp::dev::IAxisInfo* iAxisInfo{nullptr};
74 std::vector<std::string> jointNames;
75 size_t subdevice_joints {0};
76
77
78 rclcpp::Node::SharedPtr m_node;
79 rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr m_publisher_laser;
80 rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr m_publisher_joint;
81 bool m_isDeviceReady = false;
82 yarp::sig::Vector m_times;
83
84 double m_minAngle, m_maxAngle;
85 double m_minDistance, m_maxDistance;
86 double m_resolution;
87 sensor_msgs::msg::JointState m_ros_struct;
88};
89
90#endif // YARP_ROS2_RANGEFINDER2D_CONTROLBOARD_NWS_ROS2_H
define control board standard interfaces
This class is the parameters parser for class Rangefinder2D_controlBoard_nws_ros2.
Rangefinder2D_nws_ros2: A Network grabber that simultaneously publishes the joint states and the meas...
bool detach() override
Detach the object (you must have first called attach).
Rangefinder2D_controlBoard_nws_ros2(const Rangefinder2D_controlBoard_nws_ros2 &)=delete
bool attach(yarp::dev::PolyDriver *driver) override
Attach to another object.
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Rangefinder2D_controlBoard_nws_ros2(Rangefinder2D_controlBoard_nws_ros2 &&) noexcept=delete
Interface implemented by all device drivers.
Interface for getting information about specific axes, if available.
Definition IAxisInfo.h:36
Control board, extend encoder interface with timestamps.
Interface for control boards implementing torque control.
Helper interface for an object that can wrap/or "attach" to a single other device.
An abstraction for a periodic thread.
The main, catch-all namespace for YARP.
Definition dirs.h:16