pr2_transmission_check_node.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
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
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     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
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 
00036 #include "pr2_transmission_check/pr2_transmission_check_node.h"
00037 #include <exception>
00038 #include <limits>
00039 #include "angles/angles.h"
00040 
00041 using namespace pr2_transmission_check;
00042 using namespace std;
00043 
00044 // Diagnostic publisher
00045 PR2TransmissionCheckNode::PR2TransmissionCheckNode() :
00046   pnh_("~"),
00047   use_sim_time_(false),
00048   disable_controller_warnings_(false),
00049   trans_status_(true)
00050 { 
00051   mech_st_sub_ = n_.subscribe("mechanism_statistics", 1000, &PR2TransmissionCheckNode::mechCallback, this);
00052   diag_pub_ = n_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00053   
00054   n_.param("/use_sim_time", use_sim_time_, false);
00055 
00056   pnh_.param("disable_controller_warnings", disable_controller_warnings_, false);
00057 
00058   TiXmlDocument xml;
00059   string robot_desc;
00060   if (!n_.getParam("robot_description", robot_desc))
00061   {
00062     ROS_ERROR("Unable to get parameters \"robot_description\" from server");
00063     throw PR2TransmissionCheckException("Unable to get parameters \"robot_description\" from server");
00064   }
00065 
00066   if (!xml.Parse(robot_desc.c_str()))
00067   {
00068     ROS_ERROR("Unable to parse XML for \"robot_description\" parameter");
00069     throw PR2TransmissionCheckException("Unable to parse \"robot_description\" XML");
00070   }
00071 
00072   TiXmlElement *robot = xml.FirstChildElement("robot");
00073   if (!robot)
00074   {
00075     ROS_ERROR("Unable to find \"robot\" element in URDF");
00076     throw PR2TransmissionCheckException("Unable to find element \"robot\" in \"robot_description\" XML");
00077   }
00078 
00079   // Check URDF init
00080   urdf::Model urdf_bot;
00081   if (!urdf_bot.initXml(robot))
00082   {
00083     ROS_ERROR("Unable to initialize URDF from robot_description");
00084     throw PR2TransmissionCheckException("Unable to initialize URDF from robot_description");
00085   }
00086 
00087   map<string, string> jnts_to_motors;
00088   loadTransmissions(robot, jnts_to_motors);
00089 
00090   loadTransCheckers(urdf_bot, jnts_to_motors);
00091 
00092 
00093   reset_srv_ = pnh_.advertiseService("reset_transmission_check", &PR2TransmissionCheckNode::reset_cb, this);
00094 
00095   trans_status_pub_ = pnh_.advertise<std_msgs::Bool>("transmission_status", 1, true);
00096 }
00097 
00098 void PR2TransmissionCheckNode::loadTransCheckers(urdf::Model &robot, map<string, string> &joints_to_actuators)
00099 {
00100   map<string, boost::shared_ptr<urdf::Joint> >::iterator it;
00101   for (it = robot.joints_.begin(); it != robot.joints_.end(); ++it)
00102   {
00103     string &jnt_name = it->second->name;
00104     if (!joints_to_actuators.count(jnt_name))
00105     {
00106       ROS_DEBUG("Joint \"%s\" wasn't found in joints to actuators map.", jnt_name.c_str());
00107       continue;
00108     }
00109     
00110     if (!it->second->calibration)
00111     {
00112       ROS_DEBUG("Joint \"%s\" doesn't have calibration. Ignoring tranmission status.", jnt_name.c_str());
00113       continue;
00114     }
00115 
00116     string &actuator_name = joints_to_actuators[jnt_name];
00117     boost::shared_ptr<TransmissionListener> tl(new TransmissionListener());
00118     if (!tl->initUrdf(it->second, actuator_name))
00119     {
00120       ROS_ERROR("Unable to initialize transmission listener for joint \"%s\".", jnt_name.c_str());
00121       continue;
00122     }
00123     trans_listeners_.push_back(tl);
00124   }
00125 }
00126 
00127 
00128 void PR2TransmissionCheckNode::mechCallback(const pr2_mechanism_msgs::MechanismStatistics::ConstPtr& mechMsg)
00129 {
00130   for (uint i = 0; i < trans_listeners_.size(); ++i)
00131     trans_listeners_[i]->update(mechMsg);
00132 }
00133 
00134 void PR2TransmissionCheckNode::loadTransmissions(TiXmlElement *robot, map<string, string> &joints_to_actuators)
00135 {
00136   TiXmlElement *xit = NULL;
00137   for (xit = robot->FirstChildElement("transmission"); xit;
00138        xit = xit->NextSiblingElement("transmission"))
00139   {
00140     std::string type(xit->Attribute("type"));
00141     
00142     if (type.find("SimpleTransmission") != string::npos)
00143     {
00144       TiXmlElement *jel = xit->FirstChildElement("joint");
00145       if (!jel)
00146       {
00147         ROS_ERROR("SimpleTransmission did not specify joint element.");
00148         continue;
00149       }
00150       string joint_name(jel->Attribute("name"));
00151 
00152 
00153       TiXmlElement *ael = xit->FirstChildElement("actuator");
00154       if (!ael)
00155       {
00156         ROS_ERROR("SimpleTransmission did not specify actuator element.");
00157         continue;
00158       }
00159       string actuator_name(ael->Attribute("name"));
00160 
00161       if (joint_name.size() == 0 || actuator_name.size() == 0)
00162       {
00163         ROS_ERROR("SimpleTransmission did not give joint or actuator name");
00164         continue;
00165       }
00166 
00167       joints_to_actuators[joint_name] = actuator_name;
00168       ROS_DEBUG("Loaded \"%s\" : \"%s\" to map", joint_name.c_str(), actuator_name.c_str());
00169     }
00170     else if (type.find("WristTransmission") != string::npos)
00171     {
00172       TiXmlElement *ract = xit->FirstChildElement("rightActuator");
00173       if (!ract)
00174       {
00175         ROS_ERROR("WristTransmission did not specify rightActuator element.");
00176         continue;
00177       }
00178       string r_actuator(ract->Attribute("name"));
00179 
00180       TiXmlElement *lact = xit->FirstChildElement("leftActuator");
00181       if (!lact)
00182       {
00183         ROS_ERROR("WristTransmission did not specify leftActuator element.");
00184         continue;
00185       }
00186       string l_actuator(lact->Attribute("name"));
00187 
00188       // Joints
00189       TiXmlElement *flex_j = xit->FirstChildElement("flexJoint");
00190       if (!flex_j)
00191       {
00192         ROS_ERROR("WristTransmission did not specify flexJoint element.");
00193         continue;
00194       }
00195       string flex_joint(flex_j->Attribute("name"));
00196 
00197       TiXmlElement *roll_j = xit->FirstChildElement("rollJoint");
00198       if (!roll_j)
00199       {
00200         ROS_ERROR("WristTransmission did not specify rollJoint element.");
00201         continue;
00202       }
00203       string roll_joint(roll_j->Attribute("name"));
00204 
00205       // Add wrist transmission to map
00206       joints_to_actuators[flex_joint] = l_actuator;
00207       joints_to_actuators[roll_joint] = r_actuator;
00208 
00209       ROS_DEBUG("Loaded wrist transmission \"%s\" : \"%s\" into map", flex_joint.c_str(), l_actuator.c_str());
00210       ROS_DEBUG("Loaded wrist transmission \"%s\" : \"%s\" into map", roll_joint.c_str(), r_actuator.c_str());
00211     }
00212   }
00213 
00214 
00215 }
00216 
00217 void PR2TransmissionCheckNode::publishDiag()
00218 {
00219   diagnostic_msgs::DiagnosticArray array;
00220   
00221   // Update with transmissions
00222   bool status = true;
00223   for (uint i = 0; i < trans_listeners_.size(); ++i)
00224   {
00225     array.status.push_back(*(trans_listeners_[i]->toDiagStat()));
00226     status = status && trans_listeners_[i]->checkOK();
00227   }
00228 
00229   array.header.stamp = ros::Time::now();
00230   diag_pub_.publish(array);
00231 
00232   // Halt motors if transmissions are broken
00233   if (!status && trans_status_)
00234   {
00235     ROS_ERROR("Halting motors, broken transmission. Check diagnostics");
00236 
00237     std_srvs::Empty::Request req;
00238     std_srvs::Empty::Response resp;
00239     ros::service::call("pr2_etherCAT/halt_motors", req, resp);
00240     
00241     trans_status_ = status;
00242   }
00243 
00244   // Publish transmission status
00245   std_msgs::Bool t_stat;
00246   t_stat.data = trans_status_;
00247   trans_status_pub_.publish(t_stat);
00248 
00249 }
00250 
00251 
00252 int main(int argc, char **argv)
00253 {
00254   ros::init(argc, argv, "pr2_transmission_check");
00255   
00256   try
00257   {
00258     PR2TransmissionCheckNode ctrlJntPub;
00259     
00260     ros::Rate pub_rate(1.0);
00261     while (ctrlJntPub.ok())
00262     {
00263       pub_rate.sleep();
00264       ros::spinOnce();
00265       ctrlJntPub.publishDiag();
00266     }
00267   }
00268   catch (PR2TransmissionCheckException &e)
00269   {
00270     ROS_FATAL("PR2TransmissionCheck node caught TransmissionCheckException. Aborting. %s", e.what());
00271     ROS_BREAK();
00272   }
00273   catch (exception& e)
00274   {
00275     ROS_FATAL("PR2TransmissionCheck node caught exception. Aborting. %s", e.what());
00276     ROS_BREAK();
00277   }
00278   
00279   exit(0);
00280   return 0;
00281 }


pr2_transmission_check
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:53:50