-
Notifications
You must be signed in to change notification settings - Fork 61
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Add support for Phidgets Humidity sensors (#173)
I have done a find and replace on the phidgets_temperature package to get the Phidgets Humidity sensor working. Tested with a `HUM1001_0`.
- Loading branch information
1 parent
0061514
commit 9e7c457
Showing
12 changed files
with
630 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,68 @@ | ||
/* | ||
* Copyright (c) 2019, Open Source Robotics Foundation | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in the | ||
* documentation and/or other materials provided with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived from | ||
* this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE | ||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR | ||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
|
||
#ifndef PHIDGETS_API_HUMIDITY_H | ||
#define PHIDGETS_API_HUMIDITY_H | ||
|
||
#include <functional> | ||
|
||
#include <libphidget22/phidget22.h> | ||
|
||
#include "phidgets_api/phidget22.h" | ||
|
||
namespace phidgets { | ||
|
||
class Humidity final | ||
{ | ||
public: | ||
PHIDGET22_NO_COPY_NO_MOVE_NO_ASSIGN(Humidity) | ||
|
||
explicit Humidity(int32_t serial_number, int hub_port, | ||
bool is_hub_port_device, | ||
std::function<void(double)> humidity_handler); | ||
|
||
~Humidity(); | ||
|
||
double getHumidity() const; | ||
|
||
void setDataInterval(uint32_t interval_ms) const; | ||
|
||
void humidityChangeHandler(double humidity) const; | ||
|
||
private: | ||
std::function<void(double)> humidity_handler_; | ||
PhidgetHumiditySensorHandle humidity_handle_; | ||
static void HumidityChangeHandler( | ||
PhidgetHumiditySensorHandle humidity_handle, void *ctx, | ||
double humidity); | ||
}; | ||
|
||
} // namespace phidgets | ||
|
||
#endif // PHIDGETS_API_HUMIDITY_H |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,102 @@ | ||
/* | ||
* Copyright (c) 2019, Open Source Robotics Foundation | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in the | ||
* documentation and/or other materials provided with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived from | ||
* this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE | ||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR | ||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
|
||
#include <functional> | ||
#include <stdexcept> | ||
|
||
#include <libphidget22/phidget22.h> | ||
|
||
#include "phidgets_api/phidget22.h" | ||
#include "phidgets_api/humidity.h" | ||
|
||
namespace phidgets { | ||
|
||
Humidity::Humidity(int32_t serial_number, int hub_port, bool is_hub_port_device, | ||
std::function<void(double)> humidity_handler) | ||
: humidity_handler_(humidity_handler) | ||
{ | ||
PhidgetReturnCode ret = PhidgetHumiditySensor_create(&humidity_handle_); | ||
if (ret != EPHIDGET_OK) | ||
{ | ||
throw Phidget22Error("Failed to create HumiditySensor handle", ret); | ||
} | ||
|
||
helpers::openWaitForAttachment( | ||
reinterpret_cast<PhidgetHandle>(humidity_handle_), serial_number, | ||
hub_port, is_hub_port_device, 0); | ||
|
||
ret = PhidgetHumiditySensor_setOnHumidityChangeHandler( | ||
humidity_handle_, HumidityChangeHandler, this); | ||
if (ret != EPHIDGET_OK) | ||
{ | ||
throw Phidget22Error("Failed to set change handler for Humidity", ret); | ||
} | ||
} | ||
|
||
Humidity::~Humidity() | ||
{ | ||
PhidgetHandle handle = reinterpret_cast<PhidgetHandle>(humidity_handle_); | ||
helpers::closeAndDelete(&handle); | ||
} | ||
|
||
double Humidity::getHumidity() const | ||
{ | ||
double current_humidity; | ||
PhidgetReturnCode ret = | ||
PhidgetHumiditySensor_getHumidity(humidity_handle_, ¤t_humidity); | ||
if (ret != EPHIDGET_OK) | ||
{ | ||
throw Phidget22Error("Failed to get humidity", ret); | ||
} | ||
return current_humidity; | ||
} | ||
|
||
void Humidity::setDataInterval(uint32_t interval_ms) const | ||
{ | ||
PhidgetReturnCode ret = | ||
PhidgetHumiditySensor_setDataInterval(humidity_handle_, interval_ms); | ||
if (ret != EPHIDGET_OK) | ||
{ | ||
throw Phidget22Error("Failed to set data interval", ret); | ||
} | ||
} | ||
|
||
void Humidity::humidityChangeHandler(double humidity) const | ||
{ | ||
humidity_handler_(humidity); | ||
} | ||
|
||
void Humidity::HumidityChangeHandler( | ||
PhidgetHumiditySensorHandle /* humidity_handle */, void *ctx, | ||
double humidity) | ||
{ | ||
((Humidity *)ctx)->humidityChangeHandler(humidity); | ||
} | ||
|
||
} // namespace phidgets |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,53 @@ | ||
cmake_minimum_required(VERSION 3.5.1) | ||
cmake_policy(SET CMP0048 NEW) | ||
project(phidgets_humidity) | ||
|
||
# Default to C++14 | ||
if(NOT CMAKE_CXX_STANDARD) | ||
set(CMAKE_CXX_STANDARD 14) | ||
endif() | ||
|
||
# High level of warnings: | ||
if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
add_compile_options(-Wall -Wextra) | ||
endif() | ||
|
||
find_package(catkin REQUIRED COMPONENTS nodelet phidgets_api roscpp roslaunch std_msgs) | ||
|
||
catkin_package( | ||
INCLUDE_DIRS include | ||
LIBRARIES phidgets_humidity | ||
CATKIN_DEPENDS nodelet phidgets_api roscpp std_msgs | ||
) | ||
|
||
include_directories(include ${catkin_INCLUDE_DIRS}) | ||
|
||
add_library(phidgets_humidity src/humidity_ros_i.cpp) | ||
add_library(phidgets_humidity_nodelet src/phidgets_humidity_nodelet.cpp) | ||
|
||
add_dependencies(phidgets_humidity ${catkin_EXPORTED_TARGETS}) | ||
add_dependencies(phidgets_humidity_nodelet ${catkin_EXPORTED_TARGETS}) | ||
|
||
target_link_libraries(phidgets_humidity ${catkin_LIBRARIES}) | ||
target_link_libraries(phidgets_humidity_nodelet ${catkin_LIBRARIES} phidgets_humidity) | ||
|
||
install(TARGETS phidgets_humidity phidgets_humidity_nodelet | ||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | ||
) | ||
|
||
install(DIRECTORY include/${PROJECT_NAME}/ | ||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} | ||
FILES_MATCHING PATTERN "*.h" | ||
) | ||
|
||
install(DIRECTORY launch | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
) | ||
|
||
install(FILES phidgets_humidity_nodelet.xml | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
) | ||
|
||
roslaunch_add_file_check(launch) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,15 @@ | ||
Phidgets humidity ROS driver | ||
============================ | ||
|
||
This is the ROS driver for Phidgets humidity sensor. The various topics, services, and parameters that the node operates with are listed below. | ||
|
||
Topics | ||
------ | ||
* `/humidity` (`std_msgs/Float64`) - The current relative humidity in %. | ||
|
||
Parameters | ||
---------- | ||
* `serial` (int) - The serial number of the phidgets humidity to connect to. If -1 (the default), connects to any humidity phidget that can be found. | ||
* `hub_port` (int) - The phidgets VINT hub port to connect to. Only used if the humidity phidget is connected to a VINT hub. Defaults to 0. | ||
* `data_interval_ms` (int) - The number of milliseconds between acquisitions of data on the device. Defaults to 500 ms. | ||
* `publish_rate` (int) - How often the driver will publish data on the ROS topic. If 0 (the default), it will publish every time there is an update from the device (so at the `data_interval_ms`). If positive, it will publish the data at that rate regardless of the acquisition interval. |
69 changes: 69 additions & 0 deletions
69
phidgets_humidity/include/phidgets_humidity/humidity_ros_i.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,69 @@ | ||
/* | ||
* Copyright (c) 2019, Open Source Robotics Foundation | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in the | ||
* documentation and/or other materials provided with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived from | ||
* this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE | ||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR | ||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
|
||
#ifndef PHIDGETS_HUMIDITY_HUMIDITY_ROS_I_H | ||
#define PHIDGETS_HUMIDITY_HUMIDITY_ROS_I_H | ||
|
||
#include <memory> | ||
#include <mutex> | ||
|
||
#include <ros/ros.h> | ||
|
||
#include "phidgets_api/humidity.h" | ||
|
||
namespace phidgets { | ||
|
||
class HumidityRosI final | ||
{ | ||
public: | ||
explicit HumidityRosI(ros::NodeHandle nh, ros::NodeHandle nh_private); | ||
|
||
private: | ||
std::unique_ptr<Humidity> humidity_; | ||
std::mutex humidity_mutex_; | ||
double last_humidity_reading_; | ||
bool got_first_data_; | ||
|
||
ros::NodeHandle nh_; | ||
ros::NodeHandle nh_private_; | ||
ros::Publisher humidity_pub_; | ||
void timerCallback(const ros::TimerEvent& event); | ||
ros::Timer timer_; | ||
int publish_rate_; | ||
std::string server_name_; | ||
std::string server_ip_; | ||
|
||
void publishLatest(); | ||
|
||
void humidityChangeCallback(double humidity); | ||
}; | ||
|
||
} // namespace phidgets | ||
|
||
#endif // PHIDGETS_HUMIDITY_HUMIDITY_ROS_I_H |
52 changes: 52 additions & 0 deletions
52
phidgets_humidity/include/phidgets_humidity/phidgets_humidity_nodelet.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,52 @@ | ||
/* | ||
* Copyright (c) 2019, Open Source Robotics Foundation | ||
* All rights reserved. | ||
* | ||
* Redistribution and use in source and binary forms, with or without | ||
* modification, are permitted provided that the following conditions are met: | ||
* | ||
* * Redistributions of source code must retain the above copyright | ||
* notice, this list of conditions and the following disclaimer. | ||
* * Redistributions in binary form must reproduce the above copyright | ||
* notice, this list of conditions and the following disclaimer in the | ||
* documentation and/or other materials provided with the distribution. | ||
* * Neither the name of the copyright holder nor the names of its | ||
* contributors may be used to endorse or promote products derived from | ||
* this software without specific prior written permission. | ||
* | ||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE | ||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR | ||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
* POSSIBILITY OF SUCH DAMAGE. | ||
*/ | ||
|
||
#ifndef PHIDGETS_HUMIDITY_PHIDGETS_HUMIDITY_NODELET_H | ||
#define PHIDGETS_HUMIDITY_PHIDGETS_HUMIDITY_NODELET_H | ||
|
||
#include <memory> | ||
|
||
#include <nodelet/nodelet.h> | ||
|
||
#include "phidgets_humidity/humidity_ros_i.h" | ||
|
||
namespace phidgets { | ||
|
||
class PhidgetsHumidityNodelet : public nodelet::Nodelet | ||
{ | ||
public: | ||
virtual void onInit(); | ||
|
||
private: | ||
std::unique_ptr<HumidityRosI> humidity_; | ||
}; | ||
|
||
} // namespace phidgets | ||
|
||
#endif // PHIDGETS_HUMIDITY_PHIDGETS_HUMIDITY_NODELET_H |
Oops, something went wrong.