gazebo_ros_controller_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef GAZEBO_CONTROLLER_MANAGER_H
31 #define GAZEBO_CONTROLLER_MANAGER_H
32 
33 #include <vector>
34 #include <map>
35 
36 #include <tinyxml.h>
37 #include <boost/thread/mutex.hpp>
38 
39 #include <ros/ros.h>
42 #include <pr2_gazebo_plugins/SetModelsJointsStates.h>
44 
45 #include <gazebo/physics/World.hh>
46 #include <gazebo/physics/Model.hh>
47 #include <gazebo/physics/physics.hh>
48 #include <gazebo/common/Time.hh>
49 #include <gazebo/common/Plugin.hh>
50 
51 #undef USE_CBQ
52 #ifdef USE_CBQ
53 #include <ros/callback_queue.h>
54 #endif
55 
56 namespace gazebo
57 {
58 
59 class GazeboRosControllerManager : public ModelPlugin
60 {
61 public:
64  void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
65 
66 protected:
67  // Inherited from gazebo::Controller
68  virtual void UpdateChild();
69 
70 private:
71 
72  gazebo::physics::ModelPtr parent_model_;
75 
80  std::vector<gazebo::physics::JointPtr> joints_;
81 
83  //private: ParamT<std::string> *setModelsJointsStatesServiceNameP;
84  //private: std::string setModelsJointsStatesServiceName;
85 
86  /*
87  * \brief read pr2.xml for actuators, and pass tinyxml node to mechanism control node's initXml.
88  */
89  void ReadPr2Xml();
90 
91  /*
92  * \brief pointer to ros node
93  */
95 
98 
100  private: bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req,
101  pr2_gazebo_plugins::SetModelsJointsStates::Response &res);
102 
104  /*
105  * \brief tmp vars for performance checking
106  */
108 
110  //ParamT<std::string> *robotParamP;
111  //ParamT<std::string> *robotNamespaceP;
112  std::string robotParam;
113  std::string robotNamespace;
114 
116 
117 #ifdef USE_CBQ
118  private: ros::CallbackQueue controller_manager_queue_;
119  private: void ControllerManagerQueueThread();
120  private: boost::thread controller_manager_callback_queue_thread_;
121 #endif
122  private: void ControllerManagerROSThread();
123  private: boost::thread ros_spinner_thread_;
124 
125  // Pointer to the model
126  private: physics::WorldPtr world;
127 
128  // Pointer to the update event connection
129  private: event::ConnectionPtr updateConnection;
130 
131  // subscribe to world stats
132  private: transport::NodePtr node;
133  private: transport::SubscriberPtr statsSub;
134  private: common::Time simTime;
135 
136 };
137 
138 }
139 
140 #endif
141 
pr2_controller_manager::ControllerManager * cm_
std::string robotParam
set topic name of robot description parameter
std::vector< gazebo::physics::JointPtr > joints_
ros::ServiceServer setModelsJointsStatesService
ros service
pr2_hardware_interface::HardwareInterface hw_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
pr2_mechanism_model::RobotState * fake_state_
bool setModelsJointsStates(pr2_gazebo_plugins::SetModelsJointsStates::Request &req, pr2_gazebo_plugins::SetModelsJointsStates::Response &res)
ros service callback


pr2_gazebo_plugins
Author(s): John Hsu
autogenerated on Wed Apr 13 2022 02:59:42