tree.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, PAL Robotics S.L.
3  * All rights reserved.
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Author: Marcus Liebhardt
9  *
10  * This class has been derived from the chain class in the
11  * pr2_mechanism_model package in the pr2_mechanism stack for ROS
12  * written by Stuart Glaser and Wim Meeussen.
13  *
14  * Redistribution and use in source and binary forms, with or without
15  * modification, are permitted provided that the following conditions are met:
16  *
17  * * Redistributions of source code must retain the above copyright
18  * notice, this list of conditions and the following disclaimer.
19  * * Redistributions in binary form must reproduce the above copyright
20  * notice, this list of conditions and the following disclaimer in the
21  * documentation and/or other materials provided with the distribution.
22  * * Neither the name of the Willow Garage, Inc. nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
30  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
31  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
32  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
33  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
34  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
35  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  */
38 
41 
42 namespace pr2_mechanism_model
43 {
44 
45 bool Tree::init(RobotState *robot_state)
46 {
47  KDL::SegmentMap segmentMap;
48 
49  // construct the kdl tree
51  {
52  ROS_ERROR("Failed to construct KDL:Tree from robot_state's URDF model! Aborting ...");
53  }
54  else
55  {
56  ROS_INFO("KDL::Tree successful created.");
57 
58  segmentMap = kdl_tree_.getSegments();
59  }
60 
61  // the first step of extracting the joints from the tree is to go through all tree_elements, check for a joint,
62  // and check in case a joint is found, if it is not of not of type KDL::Joint::None
63 
64  // map for saving the temporary result of the joint extraction from the tree
65  std::map<unsigned int, std::string> jointMap;
66 
67  ROS_DEBUG("Extracting all joints from the tree, which are not of type KDL::Joint::None.");
68  for (KDL::SegmentMap::const_iterator seg_it = segmentMap.begin(); seg_it != segmentMap.end(); ++seg_it)
69  {
70  if (seg_it->second.segment.getJoint().getType() != KDL::Joint::None)
71  jointMap[seg_it->second.q_nr] = seg_it->second.segment.getJoint().getName().c_str();
72  }
73 
74  // in the second step the joints found get checked, if they appear in the JointState vector of the robot
75  ROS_DEBUG("Checking, if extracted joints can be found in the JointState vector of the robot.");
76  joints_.clear();
77  for (std::map<unsigned int, std::string>::const_iterator jnt_it = jointMap.begin();
78  jnt_it != jointMap.end(); ++jnt_it)
79  {
80  JointState* jnt = robot_state->getJointState(jnt_it->second.c_str());
81  if (!jnt)
82  {
83  ROS_ERROR("Joint '%s' has not been found in the robot's joint state vector! Aborting ...",
84  jnt_it->second.c_str());
85  return false;
86  }
87  joints_.push_back(jnt);
88  }
89 
90  ROS_DEBUG("The result after joint extraction and checking:");
91  for (unsigned int i = 0; i < joints_.size(); ++i)
92  {
93  ROS_DEBUG("joints_[%d]: joint_.name = %s", i, joints_[i]->joint_->name.c_str());
94  }
95 
96  ROS_INFO("Added %i joints", int(joints_.size()));
97 
98  return true;
99 }
100 
101 } // namespace
102 
bool init(RobotState *robot_state)
initializes the tree object The initializer&#39;s most important functionality is to create a vector of j...
Definition: tree.cpp:45
KDL_PARSER_PUBLIC bool treeFromUrdfModel(const urdf::ModelInterface &robot_model, KDL::Tree &tree)
const SegmentMap & getSegments() const
#define ROS_ERROR(...)
std::map< std::string, TreeElement > SegmentMap
#define ROS_DEBUG(...)
std::vector< JointState * > joints_
a vector of pointers to joint states; includes only the ones that can be actuated (not fixed joints) ...
Definition: tree.h:119
#define ROS_INFO(...)
This class provides the controllers with an interface to the robot state.
Definition: robot.h:126
Robot * model_
The robot model containing the transmissions, urdf robot model, and hardware interface.
Definition: robot.h:133
JointState * getJointState(const std::string &name)
Get a joint state by name.
Definition: robot.cpp:203
KDL::Tree kdl_tree_
Definition: tree.h:117
urdf::Model robot_model_
The kinematic/dynamic model of the robot.
Definition: robot.h:91


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Tue Mar 7 2023 03:54:53