This repository contains a ROS package designed to control devices of the RoCKIn Home Automation Network directly. When using this package, commands will NOT go through the RoCKIn@Home Referee, Scoring and Benchmarking Box.
Here are provided:
- The roah_devices node, that provides ROS services and topics to control the devices;
- A dummy server so that the real devices are not needed for testing.
You need to use at least ROS Hydro.
This was tested with Ubuntu 12.04.5 LTS (Precise Pangolin) and 14.04.1 LTS (Trusty Tahr).
Compile as a normal ROS package in your Catkin workspace.
Run the ROS node roah_devices
either manually or using the
launch file:
roslaunch roah_devices run_real.launch
For a quick test with the dummy server, use:
roslaunch roah_devices run_dummy.launch
Use the launch file:
roslaunch roah_devices control_real.launch
For a quick test with the dummy server, use:
roslaunch roah_devices control_dummy.launch
Output devices can be controlled by the available services:
/devices/blinds/max
/devices/blinds/min
/devices/blinds/set
/devices/dimmer/max
/devices/dimmer/min
/devices/dimmer/set
/devices/switch_1/off
/devices/switch_1/on
/devices/switch_1/set
/devices/switch_2/off
/devices/switch_2/on
/devices/switch_2/set
/devices/switch_3/off
/devices/switch_3/on
/devices/switch_3/set
The set
services take an integer parameter: 0 or 1 for the switches
and a percentage from 0 to 100 for the dimmer and blinds. All other
services take no parameters and act simply as shortcuts to the
respective set
service.
Services can easily be called from the command line:
rosservice call /devices/switch_2/on
rosservice call /devices/dimmer/set 50
Or from C++ code:
#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include <roah_devices/Bool.h>
#include <roah_devices/Percentage.h>
int main (int argc, char** argv)
{
ros::init (argc, argv, "try_service_call");
ros::NodeHandle nh;
// Call /devices/switch_2/on
if (ros::service::waitForService ("/devices/switch_2/on", 100)) {
std_srvs::Empty s;
if (! ros::service::call ("/devices/switch_2/on", s)) {
ROS_ERROR ("Error calling service");
}
}
else {
ROS_ERROR ("Could not find service");
}
// Call /devices/dimmer/set
if (ros::service::waitForService ("/devices/dimmer/set", 100)) {
roah_devices::Percentage p;
p.request.data = 75;
if (! ros::service::call ("/devices/dimmer/set", p)) {
ROS_ERROR ("Error calling service");
}
}
else {
ROS_ERROR ("Could not find service");
}
ros::spinOnce();
return 0;
}
Don't forget that your ROS package must depend on std_srvs and roah_devices.
(Python should also be easy, contribution of an example is welcome.)
Bell rings can be detected by subscribing to the topic
/devices/bell
. This topic passes no data, when an empty message is
published it means the bell was rung.
The bell can be monitored from the command line:
rostopic echo /devices/bell
Or from C++ code:
#include <ros/ros.h>
#include <std_msgs/Empty.h>
void callback(std_msgs::Empty::ConstPtr const& /*msg*/){
ROS_INFO("The bell was rung!");
}
int main (int argc, char** argv)
{
ros::init (argc, argv, "try_bell_sub");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("/devices/bell", 1, callback);
ros::spin();
return 0;
}
Don't forget that your ROS package must depend on std_msgs.
(Python should also be easy, contribution of an example is welcome.)
Mock bell rings can be generated by calling a service:
rosservice call /devices/bell/mock
The state of all devices can be monitored with the topic
/devices/state
.
From the command line just do:
rostopic echo /devices/state
For the bell, the ring is detected by detecting a difference in the timestamp. If the timestamp changes, the bell rung. If everything is running on the same machine or the machines are synchronized with NTP, the timestamp reflects the moment the bell was last rung.
When the node starts, the state is set to 0 on all devices. It is not possible to acquire hardware state.