gazebo_ros_hand_of_god.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Open Source Robotics Foundation
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 Open Source Robotics Foundation
18  * nor the names of its contributors may be
19  * used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
44 #ifdef ENABLE_PROFILER
45 #include <ignition/common/Profiler.hh>
46 #endif
47 #include <ros/ros.h>
48 
49 namespace gazebo
50 {
51  // Register this plugin with the simulator
52  GZ_REGISTER_MODEL_PLUGIN(GazeboRosHandOfGod);
53 
55  // Constructor
57  ModelPlugin(),
58  robot_namespace_(""),
59  frame_id_("hog"),
60  kl_(200),
61  ka_(200)
62  {
63  }
64 
66  // Destructor
68  {
69  }
70 
72  // Load the controller
73  void GazeboRosHandOfGod::Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
74  {
75  // Make sure the ROS node for Gazebo has already been initalized
76  if (!ros::isInitialized()) {
77  ROS_FATAL_STREAM_NAMED("hand_of_god", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
78  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
79  return;
80  }
81 
82  // Get sdf parameters
83  if(_sdf->HasElement("robotNamespace")) {
84  this->robot_namespace_ = _sdf->Get<std::string>("robotNamespace") + "/";
85  }
86 
87  if(_sdf->HasElement("frameId")) {
88  this->frame_id_ = _sdf->Get<std::string>("frameId");
89  }
90 
91  if(_sdf->HasElement("kl")) {
92  this->kl_ = _sdf->Get<double>("kl");
93  }
94  if(_sdf->HasElement("ka")) {
95  this->ka_ = _sdf->Get<double>("ka");
96  }
97 
98  if(_sdf->HasElement("linkName")) {
99  this->link_name_ = _sdf->Get<std::string>("linkName");
100  } else {
101  ROS_FATAL_STREAM_NAMED("hand_of_god", "The hand-of-god plugin requires a `linkName` parameter tag");
102  return;
103  }
104 
105  // Store the model
106  model_ = _parent;
107 
108  // Get the floating link
109  floating_link_ = model_->GetLink(link_name_);
110  // Disable gravity for the hog
111  floating_link_->SetGravityMode(false);
112  if(!floating_link_) {
113  ROS_ERROR_NAMED("hand_of_god", "Floating link not found");
114  const std::vector<physics::LinkPtr> &links = model_->GetLinks();
115  for(unsigned i=0; i < links.size(); i++) {
116  ROS_ERROR_STREAM_NAMED("hand_of_god", " -- Link "<<i<<": "<<links[i]->GetName());
117  }
118  return;
119  }
120 
121 #if GAZEBO_MAJOR_VERSION >= 8
122  cl_ = 2.0 * sqrt(kl_*floating_link_->GetInertial()->Mass());
123  ca_ = 2.0 * sqrt(ka_*floating_link_->GetInertial()->IXX());
124 #else
125  cl_ = 2.0 * sqrt(kl_*floating_link_->GetInertial()->GetMass());
126  ca_ = 2.0 * sqrt(ka_*floating_link_->GetInertial()->GetIXX());
127 #endif
128 
129  // Create the TF listener for the desired position of the hog
130  tf_buffer_.reset(new tf2_ros::Buffer());
133 
134  // Register update event handler
135  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
136  boost::bind(&GazeboRosHandOfGod::GazeboUpdate, this));
137  }
138 
140  // Update the controller
142  {
143 #ifdef ENABLE_PROFILER
144  IGN_PROFILE("GazeboRosHandOfGod::GazeboUpdate");
145 #endif
146  // Get TF transform relative to the /world link
147  geometry_msgs::TransformStamped hog_desired_tform;
148  static bool errored = false;
149  try{
150  hog_desired_tform = tf_buffer_->lookupTransform("world", frame_id_+"_desired", ros::Time(0));
151  errored = false;
152  } catch (tf2::TransformException ex){
153  if(!errored) {
154  ROS_ERROR_NAMED("hand_of_god", "%s",ex.what());
155  errored = true;
156  }
157  return;
158  }
159 #ifdef ENABLE_PROFILER
160  IGN_PROFILE_BEGIN("Convert TF transform to Gazebo Pose");
161 #endif
162  // Convert TF transform to Gazebo Pose
163  const geometry_msgs::Vector3 &p = hog_desired_tform.transform.translation;
164  const geometry_msgs::Quaternion &q = hog_desired_tform.transform.rotation;
165  ignition::math::Pose3d hog_desired(
166  ignition::math::Vector3d(p.x, p.y, p.z),
167  ignition::math::Quaterniond(q.w, q.x, q.y, q.z));
168 
169  // Relative transform from actual to desired pose
170 #if GAZEBO_MAJOR_VERSION >= 8
171  ignition::math::Pose3d world_pose = floating_link_->DirtyPose();
172  ignition::math::Vector3d worldLinearVel = floating_link_->WorldLinearVel();
173  ignition::math::Vector3d relativeAngularVel = floating_link_->RelativeAngularVel();
174 #else
175  ignition::math::Pose3d world_pose = floating_link_->GetDirtyPose().Ign();
176  ignition::math::Vector3d worldLinearVel = floating_link_->GetWorldLinearVel().Ign();
177  ignition::math::Vector3d relativeAngularVel = floating_link_->GetRelativeAngularVel().Ign();
178 #endif
179  ignition::math::Vector3d err_pos = hog_desired.Pos() - world_pose.Pos();
180  // Get exponential coordinates for rotation
181  ignition::math::Quaterniond err_rot = (ignition::math::Matrix4d(world_pose.Rot()).Inverse()
182  * ignition::math::Matrix4d(hog_desired.Rot())).Rotation();
183  ignition::math::Quaterniond not_a_quaternion = err_rot.Log();
184 #ifdef ENABLE_PROFILER
185  IGN_PROFILE_END();
186  IGN_PROFILE_BEGIN("fill ROS message");
187 #endif
188  floating_link_->AddForce(
189  kl_ * err_pos - cl_ * worldLinearVel);
190 
191  floating_link_->AddRelativeTorque(
192  ka_ * ignition::math::Vector3d(not_a_quaternion.X(), not_a_quaternion.Y(), not_a_quaternion.Z())
193  - ca_ * relativeAngularVel);
194 
195  // Convert actual pose to TransformStamped message
196  geometry_msgs::TransformStamped hog_actual_tform;
197 
198  hog_actual_tform.header.frame_id = "world";
199  hog_actual_tform.header.stamp = ros::Time::now();
200 
201  hog_actual_tform.child_frame_id = frame_id_ + "_actual";
202 
203  hog_actual_tform.transform.translation.x = world_pose.Pos().X();
204  hog_actual_tform.transform.translation.y = world_pose.Pos().Y();
205  hog_actual_tform.transform.translation.z = world_pose.Pos().Z();
206 
207  hog_actual_tform.transform.rotation.w = world_pose.Rot().W();
208  hog_actual_tform.transform.rotation.x = world_pose.Rot().X();
209  hog_actual_tform.transform.rotation.y = world_pose.Rot().Y();
210  hog_actual_tform.transform.rotation.z = world_pose.Rot().Z();
211 #ifdef ENABLE_PROFILER
212  IGN_PROFILE_END();
213  IGN_PROFILE_BEGIN("sendTransform");
214 #endif
215  tf_broadcaster_->sendTransform(hog_actual_tform);
216 #ifdef ENABLE_PROFILER
217  IGN_PROFILE_END();
218 #endif
219  }
220 
221 }
gazebo::GazeboRosHandOfGod::model_
physics::ModelPtr model_
Definition: gazebo_ros_hand_of_god.h:59
gazebo::GazeboRosHandOfGod::tf_broadcaster_
boost::shared_ptr< tf2_ros::TransformBroadcaster > tf_broadcaster_
Definition: gazebo_ros_hand_of_god.h:58
gazebo
gazebo_ros_hand_of_god.h
ros.h
gazebo::GazeboRosHandOfGod::link_name_
std::string link_name_
Definition: gazebo_ros_hand_of_god.h:61
gazebo::GazeboRosHandOfGod::GazeboUpdate
virtual void GazeboUpdate()
Update the controller.
Definition: gazebo_ros_hand_of_god.cpp:174
gazebo::GazeboRosHandOfGod::GazeboRosHandOfGod
GazeboRosHandOfGod()
Constructor.
Definition: gazebo_ros_hand_of_god.cpp:89
gazebo::GazeboRosHandOfGod::ka_
double ka_
Definition: gazebo_ros_hand_of_god.h:64
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
gazebo::GazeboRosHandOfGod::ca_
double ca_
Definition: gazebo_ros_hand_of_god.h:65
gazebo::GazeboRosHandOfGod::kl_
double kl_
Definition: gazebo_ros_hand_of_god.h:64
tf2_ros::TransformListener
gazebo::GazeboRosHandOfGod::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_hand_of_god.h:62
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
gazebo::GazeboRosHandOfGod::tf_buffer_
boost::shared_ptr< tf2_ros::Buffer > tf_buffer_
Definition: gazebo_ros_hand_of_god.h:56
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosHandOfGod::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_hand_of_god.cpp:106
tf2_ros::Buffer
gazebo::GazeboRosHandOfGod::floating_link_
physics::LinkPtr floating_link_
Definition: gazebo_ros_hand_of_god.h:60
gazebo::GazeboRosHandOfGod::cl_
double cl_
Definition: gazebo_ros_hand_of_god.h:65
gazebo::GazeboRosHandOfGod::frame_id_
std::string frame_id_
Definition: gazebo_ros_hand_of_god.h:63
ros::Time
tf2_ros::TransformBroadcaster
gazebo::GazeboRosHandOfGod::~GazeboRosHandOfGod
virtual ~GazeboRosHandOfGod()
Destructor.
Definition: gazebo_ros_hand_of_god.cpp:100
tf2::TransformException
gazebo::GazeboRosHandOfGod::tf_listener_
boost::shared_ptr< tf2_ros::TransformListener > tf_listener_
Definition: gazebo_ros_hand_of_god.h:57
gazebo::GazeboRosHandOfGod::update_connection_
event::ConnectionPtr update_connection_
Pointer to the update event connection.
Definition: gazebo_ros_hand_of_god.h:55
ros::Time::now
static Time now()


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Nov 23 2023 03:50:28