22 int main(
int argc,
char **argv)
28 std::string update_mode;
29 std::vector<std::shared_ptr<Phidget>> phidgets;
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;
36 nh.
param<
int>(
"frequency",freq, 30);
37 nh.
param<std::string>(
"update_mode", update_mode,
"polling");
41 if(nh.
getParam(
"boards",phidget_params))
43 for(
auto& board : phidget_params)
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"))
49 ROS_ERROR(
"Board '%s' has no serial_num param in phidget yaml config",board_name.c_str());
56 if(!sensors_nh.
getParam(
"sensors", board_param))
58 ROS_ERROR(
"Board '%s' has no sensors param in phidget yaml config",board_name.c_str());
61 phidget_params_map.insert(std::make_pair(board_desc[
"serial_num"],
62 std::make_pair(board_name, board_param)));
67 ROS_WARN(
"No params for the phidget boards on the Paramserver using default name/port values");
77 if(update_mode ==
"event")
79 else if(update_mode ==
"polling")
83 ROS_WARN(
"Unknown update mode '%s' use polling instead", update_mode.c_str());
88 if(devices.size() > 0)
91 for(
auto& device : devices)
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;
96 if(sensors_param !=
nullptr)
97 name = (*phidget_params_map_itr).second.first;
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;
105 std::make_shared<PhidgetIKROS>(nodeHandle, device.serial_num, name, sensors_param, sensMode));
114 for(
auto& phidget : phidgets)
125 ROS_ERROR(
"Phidget Manager could not find any attached devices");
auto getAttachedDevices() -> std::vector< AttachedDevice >
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool getParam(const std::string &key, std::string &s) const
ROSCPP_DECL void spinOnce()