phidget_sensors_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <ros/ros.h>
21 
22 int main(int argc, char **argv)
23 {
24  //init ros
25  ros::init(argc, argv, "cob_phidgets");
26 
27  int freq;
28  std::string update_mode;
29  std::vector<std::shared_ptr<Phidget>> phidgets;
30  ros::NodeHandle nodeHandle;
31  ros::NodeHandle nh("~");
32  std::map<int, std::pair<std::string, XmlRpc::XmlRpcValue> > phidget_params_map;
33  std::map<int, std::pair<std::string, XmlRpc::XmlRpcValue> >::iterator phidget_params_map_itr;
34 
35  //get default params from server
36  nh.param<int>("frequency",freq, 30);
37  nh.param<std::string>("update_mode", update_mode, "polling");
38 
39  //get board params from server
40  XmlRpc::XmlRpcValue phidget_params;
41  if(nh.getParam("boards",phidget_params))
42  {
43  for(auto& board : phidget_params)
44  {
45  std::string board_name = board.first;
46  ROS_DEBUG("Found Board with name '%s' in params", board_name.c_str());
47  if(!board.second.hasMember("serial_num"))
48  {
49  ROS_ERROR("Board '%s' has no serial_num param in phidget yaml config",board_name.c_str());
50  continue;
51  }
52  XmlRpc::XmlRpcValue board_desc = board.second;
53  ros::NodeHandle boards_nh(nh, "boards");
54  ros::NodeHandle sensors_nh(boards_nh, board_name);
55  XmlRpc::XmlRpcValue board_param;
56  if(!sensors_nh.getParam("sensors", board_param))
57  {
58  ROS_ERROR("Board '%s' has no sensors param in phidget yaml config",board_name.c_str());
59  continue;
60  }
61  phidget_params_map.insert(std::make_pair(board_desc["serial_num"],
62  std::make_pair(board_name, board_param)));
63  }
64  }
65  else
66  {
67  ROS_WARN("No params for the phidget boards on the Paramserver using default name/port values");
68  }
69 
70  //look for attached devices
71  PhidgetManager* manager = new PhidgetManager();
72  auto devices = manager->getAttachedDevices();
73  delete manager;
74 
75  //set the update method
76  PhidgetIK::SensingMode sensMode;
77  if(update_mode == "event")
79  else if(update_mode == "polling")
81  else
82  {
83  ROS_WARN("Unknown update mode '%s' use polling instead", update_mode.c_str());
85  }
86 
87  //if no devices attached exit
88  if(devices.size() > 0)
89  {
90  //loop over all found devices and init them
91  for(auto& device : devices)
92  {
93  phidget_params_map_itr = phidget_params_map.find(device.serial_num);
94  XmlRpc::XmlRpcValue *sensors_param = (phidget_params_map_itr != phidget_params_map.end()) ? &((*phidget_params_map_itr).second.second) : nullptr;
95  std::string name;
96  if(sensors_param != nullptr)
97  name = (*phidget_params_map_itr).second.first;
98  else
99  {
100  ROS_WARN("Could not find parameters for Board with serial: %d. Using default params!", device.serial_num);
101  std::stringstream ss; ss << device.serial_num;
102  name = ss.str();
103  }
104  phidgets.push_back(
105  std::make_shared<PhidgetIKROS>(nodeHandle, device.serial_num, name, sensors_param, sensMode));
106  }
107 
108  ros::Rate loop_rate(freq);
109  while (ros::ok())
110  {
111  //update devices if update method is polling
112  if(sensMode == PhidgetIK::SensingMode::POLLING)
113  {
114  for(auto& phidget : phidgets)
115  {
116  phidget->update();
117  }
118  }
119  ros::spinOnce();
120  loop_rate.sleep();
121  }
122  }
123  else
124  {
125  ROS_ERROR("Phidget Manager could not find any attached devices");
126  }
127 
128  return 0;
129 }
auto getAttachedDevices() -> std::vector< AttachedDevice >
SensingMode
Definition: phidget.h:27
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
int main(int argc, char **argv)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
bool sleep()
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


cob_phidgets
Author(s): Florian Weisshardt
autogenerated on Wed Apr 7 2021 02:11:43