Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00043 #include <gazebo_plugins/gazebo_ros_hand_of_god.h>
00044 #include <ros/ros.h>
00045
00046 namespace gazebo
00047 {
00048
00049 GZ_REGISTER_MODEL_PLUGIN(GazeboRosHandOfGod);
00050
00052
00053 GazeboRosHandOfGod::GazeboRosHandOfGod() :
00054 ModelPlugin(),
00055 robot_namespace_(""),
00056 frame_id_("hog"),
00057 kl_(200),
00058 ka_(200)
00059 {
00060 }
00061
00063
00064 GazeboRosHandOfGod::~GazeboRosHandOfGod()
00065 {
00066 }
00067
00069
00070 void GazeboRosHandOfGod::Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf )
00071 {
00072
00073 if (!ros::isInitialized()) {
00074 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00075 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00076 return;
00077 }
00078
00079
00080 if(_sdf->HasElement("robotNamespace")) {
00081 this->robot_namespace_ = _sdf->Get<std::string>("robotNamespace") + "/";
00082 }
00083
00084 if(_sdf->HasElement("frameId")) {
00085 this->frame_id_ = _sdf->Get<std::string>("frameId");
00086 }
00087
00088 if(_sdf->HasElement("kl")) {
00089 this->kl_ = _sdf->Get<double>("kl");
00090 }
00091 if(_sdf->HasElement("ka")) {
00092 this->ka_ = _sdf->Get<double>("ka");
00093 }
00094
00095 if(_sdf->HasElement("linkName")) {
00096 this->link_name_ = _sdf->Get<std::string>("linkName");
00097 } else {
00098 ROS_FATAL_STREAM("The hand-of-god plugin requires a `linkName` parameter tag");
00099 return;
00100 }
00101
00102
00103 model_ = _parent;
00104
00105
00106 floating_link_ = model_->GetLink(link_name_);
00107
00108 floating_link_->SetGravityMode(false);
00109 if(!floating_link_) {
00110 ROS_ERROR("Floating link not found!");
00111 const std::vector<physics::LinkPtr> &links = model_->GetLinks();
00112 for(unsigned i=0; i < links.size(); i++) {
00113 ROS_ERROR_STREAM(" -- Link "<<i<<": "<<links[i]->GetName());
00114 }
00115 return;
00116 }
00117
00118 cl_ = 2.0 * sqrt(kl_*floating_link_->GetInertial()->GetMass());
00119 ca_ = 2.0 * sqrt(ka_*floating_link_->GetInertial()->GetIXX());
00120
00121
00122 tf_buffer_.reset(new tf2_ros::Buffer());
00123 tf_listener_.reset(new tf2_ros::TransformListener(*tf_buffer_));
00124 tf_broadcaster_.reset(new tf2_ros::TransformBroadcaster());
00125
00126
00127 this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
00128 boost::bind(&GazeboRosHandOfGod::GazeboUpdate, this));
00129 }
00130
00132
00133 void GazeboRosHandOfGod::GazeboUpdate()
00134 {
00135
00136 geometry_msgs::TransformStamped hog_desired_tform;
00137 static bool errored = false;
00138 try{
00139 hog_desired_tform = tf_buffer_->lookupTransform("world", frame_id_+"_desired", ros::Time(0));
00140 errored = false;
00141 } catch (tf2::TransformException ex){
00142 if(!errored) {
00143 ROS_ERROR("%s",ex.what());
00144 errored = true;
00145 }
00146 return;
00147 }
00148
00149
00150 const geometry_msgs::Vector3 &p = hog_desired_tform.transform.translation;
00151 const geometry_msgs::Quaternion &q = hog_desired_tform.transform.rotation;
00152 gazebo::math::Pose hog_desired(
00153 gazebo::math::Vector3(p.x, p.y, p.z),
00154 gazebo::math::Quaternion(q.w, q.x, q.y, q.z));
00155
00156
00157 gazebo::math::Pose world_pose = floating_link_->GetDirtyPose();
00158 gazebo::math::Vector3 err_pos = hog_desired.pos - world_pose.pos;
00159
00160 gazebo::math::Quaternion err_rot = (world_pose.rot.GetAsMatrix4().Inverse() * hog_desired.rot.GetAsMatrix4()).GetRotation();
00161 gazebo::math::Quaternion not_a_quaternion = err_rot.GetLog();
00162
00163 floating_link_->AddForce(
00164 kl_ * err_pos - cl_ * floating_link_->GetWorldLinearVel());
00165
00166 floating_link_->AddRelativeTorque(
00167 ka_ * gazebo::math::Vector3(not_a_quaternion.x, not_a_quaternion.y, not_a_quaternion.z) - ca_ * floating_link_->GetRelativeAngularVel());
00168
00169
00170 geometry_msgs::TransformStamped hog_actual_tform;
00171
00172 hog_actual_tform.header.frame_id = "world";
00173 hog_actual_tform.header.stamp = ros::Time::now();
00174
00175 hog_actual_tform.child_frame_id = frame_id_ + "_actual";
00176
00177 hog_actual_tform.transform.translation.x = world_pose.pos.x;
00178 hog_actual_tform.transform.translation.y = world_pose.pos.y;
00179 hog_actual_tform.transform.translation.z = world_pose.pos.z;
00180
00181 hog_actual_tform.transform.rotation.w = world_pose.rot.w;
00182 hog_actual_tform.transform.rotation.x = world_pose.rot.x;
00183 hog_actual_tform.transform.rotation.y = world_pose.rot.y;
00184 hog_actual_tform.transform.rotation.z = world_pose.rot.z;
00185
00186 tf_broadcaster_->sendTransform(hog_actual_tform);
00187 }
00188
00189 }