motoman_utils.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2014, Southwest Research Institute
00005  * Author: Shaun Edwards
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *  * Redistributions of source code must retain the above copyright
00013  *  notice, this list of conditions and the following disclaimer.
00014  *  * Redistributions in binary form must reproduce the above copyright
00015  *  notice, this list of conditions and the following disclaimer in the
00016  *  documentation and/or other materials provided with the distribution.
00017  *  * Neither the name of the Southwest Research Institute, nor the names
00018  *  of its contributors may be used to endorse or promote products derived
00019  *  from this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #include "motoman_driver/industrial_robot_client/motoman_utils.h"
00035 #include "ros/ros.h"
00036 
00037 namespace industrial_robot_client
00038 {
00039 namespace motoman_utils
00040 {
00041 
00042 bool getJointGroups(const std::string topic_param, std::map<int, RobotGroup> & robot_groups)
00043 {
00044   if(ros::param::has(topic_param))
00045   {
00046     XmlRpc::XmlRpcValue topics_list_rpc;
00047     ros::param::get(topic_param, topics_list_rpc);
00048 
00049 
00050     std::vector<XmlRpc::XmlRpcValue> topics_list;
00051 
00052     ROS_INFO_STREAM("Loading topic list");
00053     ROS_INFO_STREAM("Found " << topics_list_rpc.size() << " topics");
00054 
00055     for (int i = 0; i < topics_list_rpc.size(); i++)
00056     {
00057       XmlRpc::XmlRpcValue state_value;
00058       state_value = topics_list_rpc[i];
00059       ROS_INFO_STREAM("Topic(state_value): " << state_value);
00060       topics_list.push_back(state_value);
00061     }
00062 
00063 
00064     for (int i = 0; i < topics_list.size(); i++)
00065     {
00066       ROS_INFO_STREAM("Loading group: " << topics_list[i]);
00067       RobotGroup rg;
00068       std::vector<std::string> rg_joint_names;
00069 
00070       XmlRpc::XmlRpcValue joints;
00071 
00072       joints = topics_list[i]["joints"];
00073       for (int jt = 0; jt < joints.size(); jt++)
00074       {
00075         rg_joint_names.push_back(static_cast<std::string>(joints[jt]));
00076       }
00077 
00078       XmlRpc::XmlRpcValue group_number;
00079 
00080 
00081       group_number = topics_list[i]["group"];
00082       int group_number_int = static_cast<int>(group_number);
00083 
00084       XmlRpc::XmlRpcValue name;
00085       std::string name_string;
00086 
00087       name = topics_list[i]["name"];
00088       name_string = static_cast<std::string>(name);
00089 
00090       XmlRpc::XmlRpcValue ns;
00091       std::string ns_string;
00092 
00093       ns = topics_list[i]["ns"];
00094 
00095       ns_string = static_cast<std::string>(ns);
00096 
00097       ROS_DEBUG_STREAM("Setting group: " );
00098       ROS_DEBUG_STREAM("  group number: " << group_number  );
00099       ROS_DEBUG_STREAM("  group number(int): " << group_number_int  );
00100       ROS_DEBUG_STREAM("  joints_names(size): " << rg_joint_names.size()  );
00101       ROS_DEBUG_STREAM("  name: " << name_string  );
00102       ROS_DEBUG_STREAM("  ns: " << ns_string );
00103       rg.set_group_id(group_number_int);
00104       rg.set_joint_names(rg_joint_names);
00105       rg.set_name(name_string);
00106       rg.set_ns(ns_string);
00107 
00108       robot_groups[group_number] = rg;
00109     }
00110 
00111     ROS_INFO_STREAM("Loaded " << robot_groups.size() << " groups");
00112     return true;
00113   }
00114   else
00115   {
00116     ROS_ERROR_STREAM("Failed to find " << topic_param << " parameter");
00117     return false;
00118   }
00119 }
00120 
00121 } //motoman_utils
00122 } //industrial_robot_client
00123 


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:58