Skip to content

Commit 39f8fb9

Browse files
authored
Merge pull request #82 from elandini84/fix/ReturnValue/Rangefinder2D
Rangefinder2D_nwc_yarp compatibility fix
2 parents 59cd939 + 2d24f91 commit 39f8fb9

File tree

4 files changed

+55
-55
lines changed

4 files changed

+55
-55
lines changed

.github/workflows/conda-ci.yml

+5-5
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ jobs:
3838
- name: Check License
3939
run: |
4040
perl tests/misc/check_license.pl
41-
41+
4242
check-tests:
4343
name: 'Check Devices Tests'
4444
runs-on: ubuntu-20.04
@@ -52,7 +52,7 @@ jobs:
5252
- name: Check Devices Tests
5353
run: |
5454
python3 tests/misc/check_tests.py
55-
55+
5656
build:
5757
name: '[${{ matrix.os }}@${{ matrix.build_type }}@${{ matrix.ros_distro }}@conda]'
5858
runs-on: ${{ matrix.os }}
@@ -83,7 +83,7 @@ jobs:
8383
if: contains(matrix.os, 'macos') || contains(matrix.os, 'ubuntu')
8484
run: |
8585
cd ${GITHUB_WORKSPACE}
86-
git clone -b yarp-3.11 https://github.com/robotology/yarp
86+
git clone -b master https://github.com/robotology/yarp
8787
8888
- name: Dependencies from source [Linux&macOS]
8989
if: contains(matrix.os, 'macos') || contains(matrix.os, 'ubuntu')
@@ -106,7 +106,7 @@ jobs:
106106
shell: bash -l {0}
107107
run: |
108108
cd ${GITHUB_WORKSPACE}
109-
git clone -b yarp-3.11 https://github.com/robotology/yarp
109+
git clone -b master https://github.com/robotology/yarp
110110
cd yarp
111111
mkdir build
112112
cd build
@@ -219,7 +219,7 @@ jobs:
219219
if: contains(matrix.os, 'macos') || contains(matrix.os, 'ubuntu')
220220
run: |
221221
cd ${GITHUB_WORKSPACE}
222-
git clone -b yarp-3.11 https://github.com/robotology/yarp
222+
git clone -b master https://github.com/robotology/yarp
223223
224224
- name: Dependencies from source [Linux&macOS]
225225
if: contains(matrix.os, 'macos') || contains(matrix.os, 'ubuntu')

CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,8 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
3131
set(YARP_FORCE_DYNAMIC_PLUGINS TRUE CACHE INTERNAL "yarp-devices-ros2 is always built with dynamic plugins")
3232
option(BUILD_SHARED_LIBS "Build libraries as shared as opposed to static" ON)
3333

34-
find_package(YARP 3.11.1 COMPONENTS os sig dev serversql OPTIONAL_COMPONENTS math REQUIRED)
35-
find_package(YARP 3.11.1 COMPONENTS catch2 dev_tests QUIET)
34+
find_package(YARP 3.11.100 COMPONENTS os sig dev serversql OPTIONAL_COMPONENTS math REQUIRED)
35+
find_package(YARP 3.11.100 COMPONENTS catch2 dev_tests QUIET)
3636

3737
if(YARP_catch2_FOUND AND YARP_dev_tests_FOUND)
3838
option(YARP_COMPILE_TESTS "Enable YARP tests" OFF)

src/devices/rangefinder2D_nwc_ros2/Rangefinder2D_nwc_ros2.cpp

+36-36
Original file line numberDiff line numberDiff line change
@@ -85,98 +85,98 @@ void Rangefinder2D_nwc_ros2::callback(sensor_msgs::msg::LaserScan::SharedPtr msg
8585
m_timestamp = (msg->header.stamp.sec + (msg->header.stamp.nanosec / 1000000000));
8686
}
8787

88-
bool Rangefinder2D_nwc_ros2::getLaserMeasurement(std::vector<yarp::sig::LaserMeasurementData> &data, double* timestamp)
88+
ReturnValue Rangefinder2D_nwc_ros2::getLaserMeasurement(std::vector<yarp::sig::LaserMeasurementData> &data, double* timestamp)
8989
{
90-
if (!m_data_valid) {return false;}
90+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
9191
std::lock_guard<std::mutex> data_guard(m_mutex);
9292
*timestamp = m_timestamp;
93-
return true;
93+
return ReturnValue_ok;
9494
}
9595

96-
bool Rangefinder2D_nwc_ros2::getRawData(yarp::sig::Vector &data, double* timestamp)
96+
ReturnValue Rangefinder2D_nwc_ros2::getRawData(yarp::sig::Vector &data, double* timestamp)
9797
{
98-
if (!m_data_valid) {return false;}
98+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
9999
std::lock_guard<std::mutex> data_guard(m_mutex);
100100
data = m_data;
101101
*timestamp = m_timestamp;
102-
return true;
102+
return ReturnValue_ok;
103103
}
104104

105-
bool Rangefinder2D_nwc_ros2::getDeviceStatus(Device_status& status)
105+
ReturnValue Rangefinder2D_nwc_ros2::getDeviceStatus(Device_status& status)
106106
{
107-
if (!m_data_valid) {return false;}
107+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
108108
std::lock_guard<std::mutex> data_guard(m_mutex);
109-
return true;
109+
return ReturnValue_ok;
110110
}
111111

112-
bool Rangefinder2D_nwc_ros2::getDistanceRange(double& min, double& max)
112+
ReturnValue Rangefinder2D_nwc_ros2::getDistanceRange(double& min, double& max)
113113
{
114-
if (!m_data_valid) {return false;}
114+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
115115
std::lock_guard<std::mutex> data_guard(m_mutex);
116116
min = m_minDistance;
117117
max = m_maxDistance;
118-
return true;
118+
return ReturnValue_ok;
119119
}
120120

121-
bool Rangefinder2D_nwc_ros2::setDistanceRange(double min, double max)
121+
ReturnValue Rangefinder2D_nwc_ros2::setDistanceRange(double min, double max)
122122
{
123-
if (!m_data_valid) {return false;}
123+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
124124
std::lock_guard<std::mutex> data_guard(m_mutex);
125125
yCTrace(RANGEFINDER2D_NWC_ROS2, "setDistanceRange not implemented");
126-
return false;
126+
return YARP_METHOD_NOT_YET_IMPLEMENTED();
127127
}
128128

129-
bool Rangefinder2D_nwc_ros2::getScanLimits(double& min, double& max)
129+
ReturnValue Rangefinder2D_nwc_ros2::getScanLimits(double& min, double& max)
130130
{
131-
if (!m_data_valid) {return false;}
131+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
132132
std::lock_guard<std::mutex> data_guard(m_mutex);
133133
min = m_minAngle;
134134
max = m_maxAngle;
135-
return true;
135+
return ReturnValue_ok;
136136
}
137137

138-
bool Rangefinder2D_nwc_ros2::setScanLimits(double min, double max)
138+
ReturnValue Rangefinder2D_nwc_ros2::setScanLimits(double min, double max)
139139
{
140-
if (!m_data_valid) {return false;}
140+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
141141
std::lock_guard<std::mutex> data_guard(m_mutex);
142142
yCTrace(RANGEFINDER2D_NWC_ROS2, "setScanLimits not implemented");
143-
return false;
143+
return YARP_METHOD_NOT_YET_IMPLEMENTED();
144144
}
145145

146-
bool Rangefinder2D_nwc_ros2::getHorizontalResolution(double& step)
146+
ReturnValue Rangefinder2D_nwc_ros2::getHorizontalResolution(double& step)
147147
{
148-
if (!m_data_valid) {return false;}
148+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
149149
std::lock_guard<std::mutex> data_guard(m_mutex);
150150
step = m_resolution;
151-
return true;
151+
return ReturnValue_ok;
152152
}
153153

154-
bool Rangefinder2D_nwc_ros2::setHorizontalResolution(double step)
154+
ReturnValue Rangefinder2D_nwc_ros2::setHorizontalResolution(double step)
155155
{
156-
if (!m_data_valid) {return false;}
156+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
157157
std::lock_guard<std::mutex> data_guard(m_mutex);
158158
yCTrace(RANGEFINDER2D_NWC_ROS2, "setHorizontalResolution not implemented");
159-
return false;
159+
return YARP_METHOD_NOT_YET_IMPLEMENTED();
160160
}
161161

162-
bool Rangefinder2D_nwc_ros2::getScanRate(double& rate)
162+
ReturnValue Rangefinder2D_nwc_ros2::getScanRate(double& rate)
163163
{
164-
if (!m_data_valid) {return false;}
164+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
165165
std::lock_guard<std::mutex> data_guard(m_mutex);
166-
return true;
166+
return ReturnValue_ok;
167167
}
168168

169-
bool Rangefinder2D_nwc_ros2::setScanRate(double rate)
169+
ReturnValue Rangefinder2D_nwc_ros2::setScanRate(double rate)
170170
{
171-
if (!m_data_valid) {return false;}
171+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
172172
std::lock_guard<std::mutex> data_guard(m_mutex);
173173
yCTrace(RANGEFINDER2D_NWC_ROS2, "setScanRate not implemented");
174-
return false;
174+
return YARP_METHOD_NOT_YET_IMPLEMENTED();
175175
}
176176

177-
bool Rangefinder2D_nwc_ros2::getDeviceInfo(std::string &device_info)
177+
ReturnValue Rangefinder2D_nwc_ros2::getDeviceInfo(std::string &device_info)
178178
{
179-
if (!m_data_valid) {return false;}
179+
if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic;}
180180
std::lock_guard<std::mutex> data_guard(m_mutex);
181-
return true;
181+
return ReturnValue_ok;
182182
}

src/devices/rangefinder2D_nwc_ros2/Rangefinder2D_nwc_ros2.h

+12-12
Original file line numberDiff line numberDiff line change
@@ -54,18 +54,18 @@ class Rangefinder2D_nwc_ros2 :
5454

5555
public:
5656
// IRangeFinder2D
57-
bool getLaserMeasurement(std::vector<yarp::sig::LaserMeasurementData> &data, double* timestamp = nullptr) override;
58-
bool getRawData(yarp::sig::Vector &data, double* timestamp = nullptr) override;
59-
bool getDeviceStatus(Device_status& status) override;
60-
bool getDistanceRange(double& min, double& max) override;
61-
bool setDistanceRange(double min, double max) override;
62-
bool getScanLimits(double& min, double& max) override;
63-
bool setScanLimits(double min, double max) override;
64-
bool getHorizontalResolution(double& step) override;
65-
bool setHorizontalResolution(double step) override;
66-
bool getScanRate(double& rate) override;
67-
bool setScanRate(double rate) override;
68-
bool getDeviceInfo(std::string &device_info) override;
57+
yarp::dev::ReturnValue getLaserMeasurement(std::vector<yarp::sig::LaserMeasurementData> &data, double* timestamp = nullptr) override;
58+
yarp::dev::ReturnValue getRawData(yarp::sig::Vector &data, double* timestamp = nullptr) override;
59+
yarp::dev::ReturnValue getDeviceStatus(Device_status& status) override;
60+
yarp::dev::ReturnValue getDistanceRange(double& min, double& max) override;
61+
yarp::dev::ReturnValue setDistanceRange(double min, double max) override;
62+
yarp::dev::ReturnValue getScanLimits(double& min, double& max) override;
63+
yarp::dev::ReturnValue setScanLimits(double min, double max) override;
64+
yarp::dev::ReturnValue getHorizontalResolution(double& step) override;
65+
yarp::dev::ReturnValue setHorizontalResolution(double step) override;
66+
yarp::dev::ReturnValue getScanRate(double& rate) override;
67+
yarp::dev::ReturnValue setScanRate(double rate) override;
68+
yarp::dev::ReturnValue getDeviceInfo(std::string &device_info) override;
6969

7070
private:
7171
rclcpp::Node::SharedPtr m_node;

0 commit comments

Comments
 (0)