robot_state_interface.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *  * Redistributions of source code must retain the above copyright
00011  *  notice, this list of conditions and the following disclaimer.
00012  *  * Redistributions in binary form must reproduce the above copyright
00013  *  notice, this list of conditions and the following disclaimer in the
00014  *  documentation and/or other materials provided with the distribution.
00015  *  * Neither the name of the Southwest Research Institute, nor the names
00016  *  of its contributors may be used to endorse or promote products derived
00017  *  from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include "motoman_driver/industrial_robot_client/robot_state_interface.h"
00033 #include "motoman_driver/industrial_robot_client/motoman_utils.h"
00034 #include "industrial_utils/param_utils.h"
00035 #include <map>
00036 #include <string>
00037 #include <vector>
00038 
00039 using industrial::smpl_msg_connection::SmplMsgConnection;
00040 using industrial_utils::param::getJointNames;
00041 using industrial_robot_client::motoman_utils::getJointGroups;
00042 
00043 namespace industrial_robot_client
00044 {
00045 namespace robot_state_interface
00046 {
00047 
00048 RobotStateInterface::RobotStateInterface()
00049 {
00050   this->connection_ = NULL;
00051   this->add_handler(&default_joint_handler_);
00052   this->add_handler(&default_joint_feedback_handler_);
00053   this->add_handler(&default_joint_feedback_ex_handler_);
00054   this->add_handler(&default_robot_status_handler_);
00055 }
00056 
00057 bool RobotStateInterface::init(std::string default_ip, int default_port, bool version_0)
00058 {
00059   std::string ip;
00060   int port;
00061 
00062   // override IP/port with ROS params, if available
00063   ros::param::param<std::string>("robot_ip_address", ip, default_ip);
00064   ros::param::param<int>("~port", port, default_port);
00065   // check for valid parameter values
00066   if (ip.empty())
00067   {
00068     ROS_ERROR("No valid robot IP address found.  Please set ROS 'robot_ip_address' param");
00069     return false;
00070   }
00071   if (port <= 0)
00072   {
00073     ROS_ERROR("No valid robot TCP port found.  Please set ROS '~port' param");
00074     return false;
00075   }
00076 
00077   char* ip_addr = strdup(ip.c_str());  // connection.init() requires "char*", not "const char*"
00078   ROS_INFO("Robot state connecting to IP address: '%s:%d'", ip_addr, port);
00079   default_tcp_connection_.init(ip_addr, port);
00080   free(ip_addr);
00081 
00082   return init(&default_tcp_connection_);
00083 }
00084 
00085 bool RobotStateInterface::init(SmplMsgConnection* connection)
00086 {
00087   std::map<int, RobotGroup> robot_groups;
00088   if(getJointGroups("topic_list", robot_groups))
00089   {
00090     this->version_0_ = false;
00091     return init(connection, robot_groups);
00092   }
00093   else
00094   {
00095     this->version_0_ = true;
00096     std::vector<std::string> joint_names;
00097     if (!getJointNames("controller_joint_names", "robot_description", joint_names))
00098     {
00099       ROS_WARN("Unable to read 'controller_joint_names' param.  Using standard 6-DOF joint names.");
00100     }
00101     return init(connection, joint_names);
00102   }
00103   return false;
00104 }
00105 
00106 bool RobotStateInterface::init(SmplMsgConnection* connection, std::map<int, RobotGroup> robot_groups)
00107 {
00108   ROS_INFO_STREAM(" Initializing robot state " << robot_groups.size() << " groups");
00109   this->robot_groups_ = robot_groups;
00110   this->connection_ = connection;
00111 
00112   // initialize message-manager
00113   if (!manager_.init(connection_))
00114   {
00115     ROS_ERROR("Failed to initialize message manager");
00116     return false;
00117   }
00118 
00119   // initialize default handlers
00120   if (!default_joint_handler_.init(connection_, robot_groups_))
00121   {
00122     ROS_ERROR("Failed to initialialze joint handler");
00123     return false;
00124   }
00125   this->add_handler(&default_joint_handler_);
00126 
00127   if (!default_joint_feedback_handler_.init(connection_, robot_groups_))
00128   {
00129     ROS_ERROR("Failed to initialize joint feedback handler");
00130     return false;
00131   }
00132   this->add_handler(&default_joint_feedback_handler_);
00133 
00134   if (!default_joint_feedback_ex_handler_.init(connection_, robot_groups_))
00135   {
00136     ROS_ERROR("Failed to initialize joint(extended) feedback handler");
00137     return false;
00138   }
00139   this->add_handler(&default_joint_feedback_ex_handler_);
00140 
00141   if (!default_robot_status_handler_.init(connection_))
00142   {
00143     ROS_ERROR("Failed to initialize robot status handler");
00144     return false;
00145   }
00146   this->add_handler(&default_robot_status_handler_);
00147 
00148   connection_->makeConnect();
00149 
00150   ROS_INFO("Successfully initialized robot state interface");
00151   return true;
00152 }
00153 
00154 bool RobotStateInterface::init(SmplMsgConnection* connection, std::vector<std::string>& joint_names)
00155 {
00156   this->joint_names_ = joint_names;
00157   this->connection_ = connection;
00158   connection_->makeConnect();
00159 
00160   // initialize message-manager
00161   if (!manager_.init(connection_))
00162     return false;
00163 
00164   // initialize default handlers
00165   if (!default_joint_handler_.init(connection_, joint_names_))
00166     return false;
00167   this->add_handler(&default_joint_handler_);
00168 
00169   if (!default_joint_feedback_handler_.init(connection_, joint_names_))
00170     return false;
00171   this->add_handler(&default_joint_feedback_handler_);
00172 
00173   if (!default_robot_status_handler_.init(connection_))
00174     return false;
00175   this->add_handler(&default_robot_status_handler_);
00176 
00177   return true;
00178 }
00179 
00180 void RobotStateInterface::run()
00181 {
00182   manager_.spin();
00183 }
00184 
00185 }  // namespace robot_state_interface
00186 }  // namespace industrial_robot_client


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