joint_state_listener.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, 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 /* Author: Wim Meeussen */
00036 
00037 #include <ros/ros.h>
00038 #include <urdf/model.h>
00039 #include <kdl/tree.hpp>
00040 #include <kdl_parser/kdl_parser.hpp>
00041 
00042 #include "robot_state_publisher/robot_state_publisher.h"
00043 #include "robot_state_publisher/joint_state_listener.h"
00044 
00045 using namespace std;
00046 using namespace ros;
00047 using namespace KDL;
00048 using namespace robot_state_publisher;
00049 
00050 JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m, const urdf::Model& model)
00051   : state_publisher_(tree, model), mimic_(m)
00052 {
00053   ros::NodeHandle n_tilde("~");
00054   ros::NodeHandle n;
00055 
00056   // set publish frequency
00057   double publish_freq;
00058   n_tilde.param("publish_frequency", publish_freq, 50.0);
00059   // set whether to use the /tf_static latched static transform broadcaster
00060   n_tilde.param("use_tf_static", use_tf_static_, false);
00061   // get the tf_prefix parameter from the closest namespace
00062   std::string tf_prefix_key;
00063   n_tilde.searchParam("tf_prefix", tf_prefix_key);
00064   n_tilde.param(tf_prefix_key, tf_prefix_, std::string(""));
00065   publish_interval_ = ros::Duration(1.0/max(publish_freq, 1.0));
00066 
00067   // subscribe to joint state
00068   joint_state_sub_ = n.subscribe("joint_states", 1, &JointStateListener::callbackJointState, this);
00069 
00070   // trigger to publish fixed joints
00071   // if using static transform broadcaster, this will be a oneshot trigger and only run once
00072   timer_ = n_tilde.createTimer(publish_interval_, &JointStateListener::callbackFixedJoint, this, use_tf_static_);
00073 }
00074 
00075 
00076 JointStateListener::~JointStateListener()
00077 {}
00078 
00079 
00080 void JointStateListener::callbackFixedJoint(const ros::TimerEvent& e)
00081 {
00082   state_publisher_.publishFixedTransforms(tf_prefix_, use_tf_static_);
00083 }
00084 
00085 void JointStateListener::callbackJointState(const JointStateConstPtr& state)
00086 {
00087   if (state->name.size() != state->position.size()){
00088     ROS_ERROR("Robot state publisher received an invalid joint state vector");
00089     return;
00090   }
00091 
00092   // check if we moved backwards in time (e.g. when playing a bag file)
00093   ros::Time now = ros::Time::now();
00094   if (last_callback_time_ > now) {
00095     // force re-publish of joint transforms
00096     ROS_WARN("Moved backwards in time (probably because ROS clock was reset), re-publishing joint transforms!");
00097     last_publish_time_.clear();
00098   }
00099   last_callback_time_ = now;
00100 
00101   // determine least recently published joint
00102   ros::Time last_published = now;
00103   for (unsigned int i=0; i<state->name.size(); i++) {
00104     ros::Time t = last_publish_time_[state->name[i]];
00105     last_published = (t < last_published) ? t : last_published;
00106   }
00107   // note: if a joint was seen for the first time,
00108   //       then last_published is zero.
00109 
00110   // check if we need to publish
00111   if (state->header.stamp >= last_published + publish_interval_) {
00112     // get joint positions from state message
00113     map<string, double> joint_positions;
00114     for (unsigned int i=0; i<state->name.size(); i++) {
00115       joint_positions.insert(make_pair(state->name[i], state->position[i]));
00116     }
00117 
00118     for (MimicMap::iterator i = mimic_.begin(); i != mimic_.end(); i++) {
00119       if(joint_positions.find(i->second->joint_name) != joint_positions.end()) {
00120         double pos = joint_positions[i->second->joint_name] * i->second->multiplier + i->second->offset;
00121         joint_positions.insert(make_pair(i->first, pos));
00122       }
00123     }
00124 
00125     state_publisher_.publishTransforms(joint_positions, state->header.stamp, tf_prefix_);
00126 
00127     // store publish time in joint map
00128     for (unsigned int i = 0; i<state->name.size(); i++) {
00129       last_publish_time_[state->name[i]] = state->header.stamp;
00130     }
00131   }
00132 }
00133 
00134 // ----------------------------------
00135 // ----- MAIN -----------------------
00136 // ----------------------------------
00137 int main(int argc, char** argv)
00138 {
00139   // Initialize ros
00140   ros::init(argc, argv, "robot_state_publisher");
00141   NodeHandle node;
00142 
00144   std::string exe_name = argv[0];
00145   std::size_t slash = exe_name.find_last_of("/");
00146   if (slash != std::string::npos) {
00147     exe_name = exe_name.substr(slash + 1);
00148   }
00149   if (exe_name == "state_publisher") {
00150     ROS_WARN("The 'state_publisher' executable is deprecated. Please use 'robot_state_publisher' instead");
00151   }
00153 
00154   // gets the location of the robot description on the parameter server
00155   urdf::Model model;
00156   model.initParam("robot_description");
00157   KDL::Tree tree;
00158   if (!kdl_parser::treeFromUrdfModel(model, tree)) {
00159     ROS_ERROR("Failed to extract kdl tree from xml robot description");
00160     return -1;
00161   }
00162 
00163   MimicMap mimic;
00164 
00165   for (std::map< std::string, boost::shared_ptr< urdf::Joint > >::iterator i = model.joints_.begin(); i != model.joints_.end(); i++) {
00166     if (i->second->mimic) {
00167       mimic.insert(make_pair(i->first, i->second->mimic));
00168     }
00169   }
00170 
00171   JointStateListener state_publisher(tree, mimic, model);
00172   ros::spin();
00173 
00174   return 0;
00175 }


robot_state_publisher
Author(s): Ioan Sucan , Jackie Kay , Wim Meeussen
autogenerated on Sat Feb 9 2019 04:16:45