44 #ifdef ENABLE_PROFILER
45 #include <ignition/common/Profiler.hh>
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)");
83 if(_sdf->HasElement(
"robotNamespace")) {
87 if(_sdf->HasElement(
"frameId")) {
88 this->
frame_id_ = _sdf->Get<std::string>(
"frameId");
91 if(_sdf->HasElement(
"kl")) {
92 this->
kl_ = _sdf->Get<
double>(
"kl");
94 if(_sdf->HasElement(
"ka")) {
95 this->
ka_ = _sdf->Get<
double>(
"ka");
98 if(_sdf->HasElement(
"linkName")) {
99 this->
link_name_ = _sdf->Get<std::string>(
"linkName");
114 const std::vector<physics::LinkPtr> &links =
model_->GetLinks();
115 for(
unsigned i=0; i < links.size(); i++) {
121 #if GAZEBO_MAJOR_VERSION >= 8
143 #ifdef ENABLE_PROFILER
144 IGN_PROFILE(
"GazeboRosHandOfGod::GazeboUpdate");
147 geometry_msgs::TransformStamped hog_desired_tform;
148 static bool errored =
false;
159 #ifdef ENABLE_PROFILER
160 IGN_PROFILE_BEGIN(
"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));
170 #if GAZEBO_MAJOR_VERSION >= 8
172 ignition::math::Vector3d worldLinearVel =
floating_link_->WorldLinearVel();
173 ignition::math::Vector3d relativeAngularVel =
floating_link_->RelativeAngularVel();
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();
179 ignition::math::Vector3d err_pos = hog_desired.Pos() - world_pose.Pos();
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
186 IGN_PROFILE_BEGIN(
"fill ROS message");
189 kl_ * err_pos -
cl_ * worldLinearVel);
192 ka_ * ignition::math::Vector3d(not_a_quaternion.X(), not_a_quaternion.Y(), not_a_quaternion.Z())
193 -
ca_ * relativeAngularVel);
196 geometry_msgs::TransformStamped hog_actual_tform;
198 hog_actual_tform.header.frame_id =
"world";
201 hog_actual_tform.child_frame_id =
frame_id_ +
"_actual";
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();
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
213 IGN_PROFILE_BEGIN(
"sendTransform");
216 #ifdef ENABLE_PROFILER