robot.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /*
36  * The robot model tracks the state of the robot.
37  *
38  * State path:
39  * +---------------+
40  * Actuators --> | Transmissions | --> Joints
41  * +---------------+
42  *
43  * Author: Stuart Glaser
44  */
45 
46 #ifndef ROBOT_H
47 #define ROBOT_H
48 
49 #include <vector>
50 #include <map>
51 #include <string>
52 #include <urdf/model.h>
54 #include <hardware_interface/hardware_interface.h>
57 
58 class TiXmlElement;
59 
60 // Forward declared to avoid extra includes
61 namespace pluginlib {
62 template <class T> class ClassLoader;
63 }
64 
65 namespace pr2_mechanism_model
66 {
67 
68 
78 class Robot
79 {
80 public:
83 
85  ~Robot() { }
86 
88  bool initXml(TiXmlElement *root);
89 
92 
94  std::vector<boost::shared_ptr<Transmission> > transmissions_;
95 
97  int getTransmissionIndex(const std::string &name) const;
98 
100  pr2_hardware_interface::Actuator* getActuator(const std::string &name) const;
101 
103  boost::shared_ptr<pr2_mechanism_model::Transmission> getTransmission(const std::string &name) const;
104 
106  ros::Time getTime();
107 
110 
111 private:
113 };
114 
115 
116 
127 {
128 public:
130  RobotState(Robot *model);
131 
134 
136  std::vector<JointState> joint_states_;
137 
139  JointState *getJointState(const std::string &name);
140 
142  const JointState *getJointState(const std::string &name) const;
143 
145  ros::Time getTime() {return model_->getTime();};
146 
152  std::vector<std::vector<pr2_hardware_interface::Actuator*> > transmissions_in_;
153 
159  std::vector<std::vector<pr2_mechanism_model::JointState*> > transmissions_out_;
160 
162  void propagateActuatorPositionToJointPosition();
164  void propagateJointPositionToActuatorPosition();
165 
167  void propagateJointEffortToActuatorEffort();
169  void propagateActuatorEffortToJointEffort();
170 
172  void enforceSafety();
173 
175  bool isHalted();
176 
178  void zeroCommands();
179 
180 
181  std::map<std::string, JointState*> joint_states_map_;
182 
183 };
184 
185 }
186 
187 #endif
std::vector< boost::shared_ptr< Transmission > > transmissions_
The list of transmissions.
Definition: robot.h:94
pr2_hardware_interface::HardwareInterface * hw_
a pointer to the pr2 hardware interface. Only for advanced users
Definition: robot.h:109
~Robot()
Destructor.
Definition: robot.h:85
ros::Time getTime()
Get the time when the current controller cycle was started.
Definition: robot.cpp:121
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
std::vector< std::vector< pr2_mechanism_model::JointState * > > transmissions_out_
Definition: robot.h:159
std::vector< JointState > joint_states_
The vector of joint states, in no particular order.
Definition: robot.h:136
std::map< std::string, JointState * > joint_states_map_
Definition: robot.h:181
boost::shared_ptr< pluginlib::ClassLoader< pr2_mechanism_model::Transmission > > transmission_loader_
Definition: robot.h:112
std::vector< std::vector< pr2_hardware_interface::Actuator * > > transmissions_in_
Definition: robot.h:145
This class provides the controllers with an interface to the robot model.
Definition: robot.h:78
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