@@ -85,98 +85,98 @@ void Rangefinder2D_nwc_ros2::callback(sensor_msgs::msg::LaserScan::SharedPtr msg
85
85
m_timestamp = (msg->header .stamp .sec + (msg->header .stamp .nanosec / 1000000000 ));
86
86
}
87
87
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)
89
89
{
90
- if (!m_data_valid) {return false ;}
90
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
91
91
std::lock_guard<std::mutex> data_guard (m_mutex);
92
92
*timestamp = m_timestamp;
93
- return true ;
93
+ return ReturnValue_ok ;
94
94
}
95
95
96
- bool Rangefinder2D_nwc_ros2::getRawData (yarp::sig::Vector &data, double * timestamp)
96
+ ReturnValue Rangefinder2D_nwc_ros2::getRawData (yarp::sig::Vector &data, double * timestamp)
97
97
{
98
- if (!m_data_valid) {return false ;}
98
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
99
99
std::lock_guard<std::mutex> data_guard (m_mutex);
100
100
data = m_data;
101
101
*timestamp = m_timestamp;
102
- return true ;
102
+ return ReturnValue_ok ;
103
103
}
104
104
105
- bool Rangefinder2D_nwc_ros2::getDeviceStatus (Device_status& status)
105
+ ReturnValue Rangefinder2D_nwc_ros2::getDeviceStatus (Device_status& status)
106
106
{
107
- if (!m_data_valid) {return false ;}
107
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
108
108
std::lock_guard<std::mutex> data_guard (m_mutex);
109
- return true ;
109
+ return ReturnValue_ok ;
110
110
}
111
111
112
- bool Rangefinder2D_nwc_ros2::getDistanceRange (double & min, double & max)
112
+ ReturnValue Rangefinder2D_nwc_ros2::getDistanceRange (double & min, double & max)
113
113
{
114
- if (!m_data_valid) {return false ;}
114
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
115
115
std::lock_guard<std::mutex> data_guard (m_mutex);
116
116
min = m_minDistance;
117
117
max = m_maxDistance;
118
- return true ;
118
+ return ReturnValue_ok ;
119
119
}
120
120
121
- bool Rangefinder2D_nwc_ros2::setDistanceRange (double min, double max)
121
+ ReturnValue Rangefinder2D_nwc_ros2::setDistanceRange (double min, double max)
122
122
{
123
- if (!m_data_valid) {return false ;}
123
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
124
124
std::lock_guard<std::mutex> data_guard (m_mutex);
125
125
yCTrace (RANGEFINDER2D_NWC_ROS2, " setDistanceRange not implemented" );
126
- return false ;
126
+ return YARP_METHOD_NOT_YET_IMPLEMENTED () ;
127
127
}
128
128
129
- bool Rangefinder2D_nwc_ros2::getScanLimits (double & min, double & max)
129
+ ReturnValue Rangefinder2D_nwc_ros2::getScanLimits (double & min, double & max)
130
130
{
131
- if (!m_data_valid) {return false ;}
131
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
132
132
std::lock_guard<std::mutex> data_guard (m_mutex);
133
133
min = m_minAngle;
134
134
max = m_maxAngle;
135
- return true ;
135
+ return ReturnValue_ok ;
136
136
}
137
137
138
- bool Rangefinder2D_nwc_ros2::setScanLimits (double min, double max)
138
+ ReturnValue Rangefinder2D_nwc_ros2::setScanLimits (double min, double max)
139
139
{
140
- if (!m_data_valid) {return false ;}
140
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
141
141
std::lock_guard<std::mutex> data_guard (m_mutex);
142
142
yCTrace (RANGEFINDER2D_NWC_ROS2, " setScanLimits not implemented" );
143
- return false ;
143
+ return YARP_METHOD_NOT_YET_IMPLEMENTED () ;
144
144
}
145
145
146
- bool Rangefinder2D_nwc_ros2::getHorizontalResolution (double & step)
146
+ ReturnValue Rangefinder2D_nwc_ros2::getHorizontalResolution (double & step)
147
147
{
148
- if (!m_data_valid) {return false ;}
148
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
149
149
std::lock_guard<std::mutex> data_guard (m_mutex);
150
150
step = m_resolution;
151
- return true ;
151
+ return ReturnValue_ok ;
152
152
}
153
153
154
- bool Rangefinder2D_nwc_ros2::setHorizontalResolution (double step)
154
+ ReturnValue Rangefinder2D_nwc_ros2::setHorizontalResolution (double step)
155
155
{
156
- if (!m_data_valid) {return false ;}
156
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
157
157
std::lock_guard<std::mutex> data_guard (m_mutex);
158
158
yCTrace (RANGEFINDER2D_NWC_ROS2, " setHorizontalResolution not implemented" );
159
- return false ;
159
+ return YARP_METHOD_NOT_YET_IMPLEMENTED () ;
160
160
}
161
161
162
- bool Rangefinder2D_nwc_ros2::getScanRate (double & rate)
162
+ ReturnValue Rangefinder2D_nwc_ros2::getScanRate (double & rate)
163
163
{
164
- if (!m_data_valid) {return false ;}
164
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
165
165
std::lock_guard<std::mutex> data_guard (m_mutex);
166
- return true ;
166
+ return ReturnValue_ok ;
167
167
}
168
168
169
- bool Rangefinder2D_nwc_ros2::setScanRate (double rate)
169
+ ReturnValue Rangefinder2D_nwc_ros2::setScanRate (double rate)
170
170
{
171
- if (!m_data_valid) {return false ;}
171
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
172
172
std::lock_guard<std::mutex> data_guard (m_mutex);
173
173
yCTrace (RANGEFINDER2D_NWC_ROS2, " setScanRate not implemented" );
174
- return false ;
174
+ return YARP_METHOD_NOT_YET_IMPLEMENTED () ;
175
175
}
176
176
177
- bool Rangefinder2D_nwc_ros2::getDeviceInfo (std::string &device_info)
177
+ ReturnValue Rangefinder2D_nwc_ros2::getDeviceInfo (std::string &device_info)
178
178
{
179
- if (!m_data_valid) {return false ;}
179
+ if (!m_data_valid) {return ReturnValue::return_code::return_value_error_generic ;}
180
180
std::lock_guard<std::mutex> data_guard (m_mutex);
181
- return true ;
181
+ return ReturnValue_ok ;
182
182
}
0 commit comments