phidget_sensors_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 #include <ros/ros.h>
00019 #include <cob_phidgets/phidget_manager.h>
00020 #include <cob_phidgets/phidgetik_ros.h>
00021 
00022 int main(int argc, char **argv)
00023 {
00024         //init ros
00025         ros::init(argc, argv, "cob_phidgets");
00026 
00027         int freq;
00028         std::string update_mode;
00029         std::vector<std::shared_ptr<Phidget>> phidgets;
00030         ros::NodeHandle nodeHandle;
00031         ros::NodeHandle nh("~");
00032         std::map<int, std::pair<std::string, XmlRpc::XmlRpcValue> > phidget_params_map;
00033         std::map<int, std::pair<std::string, XmlRpc::XmlRpcValue> >::iterator phidget_params_map_itr;
00034 
00035         //get default params from server
00036         nh.param<int>("frequency",freq, 30);
00037         nh.param<std::string>("update_mode", update_mode, "polling");
00038 
00039         //get board params from server
00040         XmlRpc::XmlRpcValue phidget_params;
00041         if(nh.getParam("boards",phidget_params))
00042         {
00043                 for(auto& board : phidget_params)
00044                 {
00045                         std::string board_name = board.first;
00046                         ROS_DEBUG("Found Board with name '%s' in params", board_name.c_str());
00047                         if(!board.second.hasMember("serial_num"))
00048                         {
00049                                 ROS_ERROR("Board '%s' has no serial_num param in phidget yaml config",board_name.c_str());
00050                                 continue;
00051                         }
00052                         XmlRpc::XmlRpcValue board_desc = board.second;
00053                         ros::NodeHandle boards_nh(nh, "boards");
00054                         ros::NodeHandle sensors_nh(boards_nh, board_name);
00055                         XmlRpc::XmlRpcValue board_param;
00056                         if(!sensors_nh.getParam("sensors", board_param))
00057                         {
00058                                 ROS_ERROR("Board '%s' has no sensors param in phidget yaml config",board_name.c_str());
00059                                 continue;
00060                         }
00061                         phidget_params_map.insert(std::make_pair(board_desc["serial_num"],
00062                                         std::make_pair(board_name, board_param)));
00063                 }
00064         }
00065         else
00066         {
00067                 ROS_WARN("No params for the phidget boards on the Paramserver using default name/port values");
00068         }
00069 
00070         //look for attached devices
00071         PhidgetManager* manager = new PhidgetManager();
00072         auto devices = manager->getAttachedDevices();
00073         delete manager;
00074 
00075         //set the update method
00076         PhidgetIK::SensingMode sensMode;
00077         if(update_mode == "event")
00078                 sensMode = PhidgetIK::SensingMode::EVENT;
00079         else if(update_mode == "polling")
00080                 sensMode = PhidgetIK::SensingMode::POLLING;
00081         else
00082         {
00083                 ROS_WARN("Unknown update mode '%s' use polling instead", update_mode.c_str());
00084                 sensMode = PhidgetIK::SensingMode::POLLING;
00085         }
00086 
00087         //if no devices attached exit
00088         if(devices.size() > 0)
00089         {
00090                 //loop over all found devices and init them
00091                 for(auto& device : devices)
00092                 {
00093                         phidget_params_map_itr = phidget_params_map.find(device.serial_num);
00094                         XmlRpc::XmlRpcValue *sensors_param = (phidget_params_map_itr != phidget_params_map.end()) ? &((*phidget_params_map_itr).second.second) : nullptr;
00095                         std::string name;
00096                         if(sensors_param != nullptr)
00097                                 name = (*phidget_params_map_itr).second.first;
00098                         else
00099                         {
00100                                 ROS_WARN("Could not find parameters for Board with serial: %d. Using default params!", device.serial_num);
00101                                 std::stringstream ss; ss << device.serial_num;
00102                                 name = ss.str();
00103                         }
00104                         phidgets.push_back(
00105                                 std::make_shared<PhidgetIKROS>(nodeHandle, device.serial_num, name, sensors_param, sensMode));
00106                 }
00107 
00108                 ros::Rate loop_rate(freq);
00109                 while (ros::ok())
00110                 {
00111                         //update devices if update method is polling
00112                         if(sensMode == PhidgetIK::SensingMode::POLLING)
00113                         {
00114                                 for(auto& phidget : phidgets)
00115                                 {
00116                                         phidget->update();
00117                                 }
00118                         }
00119                         ros::spinOnce();
00120                         loop_rate.sleep();
00121                 }
00122         }
00123         else
00124         {
00125                 ROS_ERROR("Phidget Manager could not find any attached devices");
00126         }
00127 
00128         return 0;
00129 }


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Sat Jun 8 2019 21:02:14