gazebo_ros_joint_pose_trajectory.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 /*
00019  * Desc: 3D position interface for ground truth.
00020  * Author: Sachin Chitta and John Hsu
00021  * Date: 1 June 2008
00022  */
00023 
00024 #include <string>
00025 #include <stdlib.h>
00026 #include <tf/tf.h>
00027 
00028 #include <gazebo_plugins/gazebo_ros_joint_pose_trajectory.h>
00029 
00030 namespace gazebo
00031 {
00032 GZ_REGISTER_MODEL_PLUGIN(GazeboRosJointPoseTrajectory);
00033 
00035 // Constructor
00036 ROS_DEPRECATED GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory()  // replaced with GazeboROSJointPoseTrajectory
00037 {
00038 
00039   this->has_trajectory_ = false;
00040   this->trajectory_index = 0;
00041   this->joint_trajectory_.points.clear();
00042   this->physics_engine_enabled_ = true;
00043   this->disable_physics_updates_ = true;
00044 }
00045 
00047 // Destructor
00048 GazeboRosJointPoseTrajectory::~GazeboRosJointPoseTrajectory()
00049 {
00050   event::Events::DisconnectWorldUpdateBegin(this->update_connection_);
00051   // Finalize the controller
00052   this->rosnode_->shutdown();
00053   this->queue_.clear();
00054   this->queue_.disable();
00055   this->callback_queue_thread_.join();
00056   delete this->rosnode_;
00057 }
00058 
00060 // Load the controller
00061 void GazeboRosJointPoseTrajectory::Load(physics::ModelPtr _model,
00062   sdf::ElementPtr _sdf)
00063 {
00064   // save pointers
00065   this->model_ = _model;
00066   this->sdf = _sdf;
00067   this->world_ = this->model_->GetWorld();
00068 
00069   // this->world_->GetPhysicsEngine()->SetGravity(math::Vector3(0, 0, 0));
00070 
00071   // load parameters
00072   this->robot_namespace_ = "";
00073   if (this->sdf->HasElement("robotNamespace"))
00074     this->robot_namespace_ = this->sdf->Get<std::string>("robotNamespace") + "/";
00075 
00076   if (!this->sdf->HasElement("serviceName"))
00077   {
00078     // default
00079     this->service_name_ = "set_joint_trajectory";
00080   }
00081   else
00082     this->service_name_ = this->sdf->Get<std::string>("serviceName");
00083 
00084   if (!this->sdf->HasElement("topicName"))
00085   {
00086     // default
00087     this->topic_name_ = "set_joint_trajectory";
00088   }
00089   else
00090     this->topic_name_ = this->sdf->Get<std::string>("topicName");
00091 
00092   if (!this->sdf->HasElement("updateRate"))
00093   {
00094     ROS_INFO("joint trajectory plugin missing <updateRate>, defaults"
00095              " to 0.0 (as fast as possible)");
00096     this->update_rate_ = 0;
00097   }
00098   else
00099     this->update_rate_ = this->sdf->Get<double>("updateRate");
00100 
00101   // Make sure the ROS node for Gazebo has already been initialized
00102   if (!ros::isInitialized())
00103   {
00104     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00105       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00106     return;
00107   }
00108 
00109   this->deferred_load_thread_ = boost::thread(
00110     boost::bind(&GazeboRosJointPoseTrajectory::LoadThread, this));
00111 
00112 }
00113 
00115 // Load the controller
00116 void GazeboRosJointPoseTrajectory::LoadThread()
00117 {
00118   this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
00119 
00120   // resolve tf prefix
00121   std::string prefix;
00122   this->rosnode_->getParam(std::string("tf_prefix"), prefix);
00123 
00124   if (this->topic_name_ != "")
00125   {
00126     ros::SubscribeOptions trajectory_so =
00127       ros::SubscribeOptions::create<trajectory_msgs::JointTrajectory>(
00128       this->topic_name_, 100, boost::bind(
00129       &GazeboRosJointPoseTrajectory::SetTrajectory, this, _1),
00130       ros::VoidPtr(), &this->queue_);
00131     this->sub_ = this->rosnode_->subscribe(trajectory_so);
00132   }
00133 
00134 #ifdef ENABLE_SERVICE
00135   if (this->service_name_ != "")
00136   {
00137     ros::AdvertiseServiceOptions srv_aso =
00138       ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointTrajectory>(
00139       this->service_name_,
00140       boost::bind(&GazeboRosJointPoseTrajectory::SetTrajectory, this, _1, _2),
00141       ros::VoidPtr(), &this->queue_);
00142     this->srv_ = this->rosnode_->advertiseService(srv_aso);
00143   }
00144 #endif
00145 
00146   this->last_time_ = this->world_->GetSimTime();
00147 
00148   // start custom queue for joint trajectory plugin ros topics
00149   this->callback_queue_thread_ =
00150     boost::thread(boost::bind(&GazeboRosJointPoseTrajectory::QueueThread, this));
00151 
00152   // New Mechanism for Updating every World Cycle
00153   // Listen to the update event. This event is broadcast every
00154   // simulation iteration.
00155   this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
00156       boost::bind(&GazeboRosJointPoseTrajectory::UpdateStates, this));
00157 }
00158 
00160 // set joint trajectory
00161 void GazeboRosJointPoseTrajectory::SetTrajectory(
00162   const trajectory_msgs::JointTrajectory::ConstPtr& trajectory)
00163 {
00164   boost::mutex::scoped_lock lock(this->update_mutex);
00165 
00166   this->reference_link_name_ = trajectory->header.frame_id;
00167   // do this every time a new joint trajectory is supplied,
00168   // use header.frame_id as the reference_link_name_
00169   if (this->reference_link_name_ != "world" &&
00170       this->reference_link_name_ != "/map" &&
00171       this->reference_link_name_ != "map")
00172   {
00173     physics::EntityPtr ent =
00174       this->world_->GetEntity(this->reference_link_name_);
00175     if (ent)
00176       this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
00177     if (!this->reference_link_)
00178     {
00179       ROS_ERROR("ros_joint_trajectory plugin needs a reference link [%s] as"
00180                 " frame_id, aborting.\n", this->reference_link_name_.c_str());
00181       return;
00182     }
00183     else
00184     {
00185       this->model_ = this->reference_link_->GetParentModel();
00186       ROS_DEBUG("test: update model pose by keeping link [%s] stationary"
00187                 " inertially", this->reference_link_->GetName().c_str());
00188     }
00189   }
00190 
00191   // copy joint configuration into a map
00192   unsigned int chain_size = trajectory->joint_names.size();
00193   this->joints_.resize(chain_size);
00194   for (unsigned int i = 0; i < chain_size; ++i)
00195   {
00196     this->joints_[i] = this->model_->GetJoint(trajectory->joint_names[i]);
00197   }
00198 
00199   unsigned int points_size = trajectory->points.size();
00200   this->points_.resize(points_size);
00201   for (unsigned int i = 0; i < points_size; ++i)
00202   {
00203     this->points_[i].positions.resize(chain_size);
00204     for (unsigned int j = 0; j < chain_size; ++j)
00205     {
00206       this->points_[i].positions[j] = trajectory->points[i].positions[j];
00207     }
00208   }
00209 
00210   // trajectory start time
00211   this->trajectory_start = gazebo::common::Time(trajectory->header.stamp.sec,
00212                                                 trajectory->header.stamp.nsec);
00213   common::Time cur_time = this->world_->GetSimTime();
00214   if (this->trajectory_start < cur_time)
00215     this->trajectory_start = cur_time;
00216 
00217   // update the joint trajectory to play
00218   this->has_trajectory_ = true;
00219   // reset trajectory_index to beginning of new trajectory
00220   this->trajectory_index = 0;
00221 
00222   if (this->disable_physics_updates_)
00223   {
00224     this->physics_engine_enabled_ = this->world_->GetEnablePhysicsEngine();
00225     this->world_->EnablePhysicsEngine(false);
00226   }
00227 }
00228 
00229 #ifdef ENABLE_SERVICE
00230 bool GazeboRosJointPoseTrajectory::SetTrajectory(
00231   const gazebo_msgs::SetJointTrajectory::Request& req,
00232   const gazebo_msgs::SetJointTrajectory::Response& res)
00233 {
00234   boost::mutex::scoped_lock lock(this->update_mutex);
00235 
00236   this->model_pose_ = req.model_pose;
00237   this->set_model_pose_ = req.set_model_pose;
00238 
00239   this->reference_link_name_ = req.joint_trajectory.header.frame_id;
00240   // do this every time a new joint_trajectory is supplied,
00241   // use header.frame_id as the reference_link_name_
00242   if (this->reference_link_name_ != "world" &&
00243       this->reference_link_name_ != "/map" &&
00244       this->reference_link_name_ != "map")
00245   {
00246     physics::EntityPtr ent =
00247       this->world_->GetEntity(this->reference_link_name_);
00248     if (ent)
00249       this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
00250     if (!this->reference_link_)
00251     {
00252       ROS_ERROR("ros_joint_trajectory plugin specified a reference link [%s]"
00253                 " that does not exist, aborting.\n",
00254                 this->reference_link_name_.c_str());
00255       ROS_DEBUG("will set model [%s] configuration, keeping model root link"
00256                 " stationary.", this->model_->GetName().c_str());
00257       return false;
00258     }
00259     else
00260       ROS_DEBUG("test: update model pose by keeping link [%s] stationary"
00261                 " inertially", this->reference_link_->GetName().c_str());
00262   }
00263 
00264   this->model_ =  this->world_->GetModel(req.model_name);
00265   if (!this->model_)  // look for it by frame_id name
00266   {
00267     this->model_ = this->reference_link_->GetParentModel();
00268     if (this->model_)
00269     {
00270       ROS_INFO("found model[%s] by link name specified in frame_id[%s]",
00271         this->model_->GetName().c_str(),
00272         req.joint_trajectory.header.frame_id.c_str());
00273     }
00274     else
00275     {
00276       ROS_WARN("no model found by link name specified in frame_id[%s],"
00277                "  aborting.", req.joint_trajectory.header.frame_id.c_str());
00278       return false;
00279     }
00280   }
00281 
00282   // copy joint configuration into a map
00283   this->joint_trajectory_ = req.joint_trajectory;
00284 
00285   // trajectory start time
00286   this->trajectory_start = gazebo::common::Time(
00287     req.joint_trajectory.header.stamp.sec,
00288     req.joint_trajectory.header.stamp.nsec);
00289 
00290   // update the joint_trajectory to play
00291   this->has_trajectory_ = true;
00292   // reset trajectory_index to beginning of new trajectory
00293   this->trajectory_index = 0;
00294   this->disable_physics_updates_ = req.disable_physics_updates;
00295   if (this->disable_physics_updates_)
00296   {
00297     this->physics_engine_enabled_ = this->world_->GetEnablePhysicsEngine();
00298     this->world_->EnablePhysicsEngine(false);
00299   }
00300 
00301   return true;
00302 }
00303 #endif
00304 
00306 // Play the trajectory, update states
00307 void GazeboRosJointPoseTrajectory::UpdateStates()
00308 {
00309   boost::mutex::scoped_lock lock(this->update_mutex);
00310   if (this->has_trajectory_)
00311   {
00312     common::Time cur_time = this->world_->GetSimTime();
00313     // roll out trajectory via set model configuration
00314     // gzerr << "i[" << trajectory_index  << "] time "
00315     //       << trajectory_start << " now: " << cur_time << " : "<< "\n";
00316     if (cur_time >= this->trajectory_start)
00317     {
00318       // @todo:  consider a while loop until the trajectory
00319       // catches up to the current time
00320       // gzerr << trajectory_index << " : "  << this->points_.size() << "\n";
00321       if (this->trajectory_index < this->points_.size())
00322       {
00323         ROS_INFO("time [%f] updating configuration [%d/%lu]",
00324           cur_time.Double(), this->trajectory_index, this->points_.size());
00325 
00326         // get reference link pose before updates
00327         math::Pose reference_pose = this->model_->GetWorldPose();
00328         if (this->reference_link_)
00329         {
00330           reference_pose = this->reference_link_->GetWorldPose();
00331         }
00332 
00333         // trajectory roll-out based on time:
00334         //  set model configuration from trajectory message
00335         unsigned int chain_size = this->joints_.size();
00336         if (chain_size ==
00337           this->points_[this->trajectory_index].positions.size())
00338         {
00339           for (unsigned int i = 0; i < chain_size; ++i)
00340           {
00341             // this is not the most efficient way to set things
00342             if (this->joints_[i])
00343 #if GAZEBO_MAJOR_VERSION >= 4
00344               this->joints_[i]->SetPosition(0,
00345 #else
00346               this->joints_[i]->SetAngle(0,
00347 #endif
00348                 this->points_[this->trajectory_index].positions[i]);
00349           }
00350 
00351           // set model pose
00352           if (this->reference_link_)
00353             this->model_->SetLinkWorldPose(reference_pose,
00354               this->reference_link_);
00355           else
00356             this->model_->SetWorldPose(reference_pose);
00357         }
00358         else
00359         {
00360           ROS_ERROR("point[%u] in JointTrajectory has different number of"
00361                     " joint names[%u] and positions[%lu].",
00362                     this->trajectory_index, chain_size,
00363                     this->points_[this->trajectory_index].positions.size());
00364         }
00365 
00366         // this->world_->SetPaused(is_paused);  // resume original pause-state
00367         gazebo::common::Time duration(
00368           this->points_[this->trajectory_index].time_from_start.sec,
00369           this->points_[this->trajectory_index].time_from_start.nsec);
00370 
00371         // reset start time for next trajectory point
00372         this->trajectory_start += duration;
00373         this->trajectory_index++;  // increment to next trajectory point
00374 
00375         // save last update time stamp
00376         this->last_time_ = cur_time;
00377       }
00378       else  // no more trajectory points
00379       {
00380         // trajectory finished
00381         this->reference_link_.reset();
00382         this->has_trajectory_ = false;
00383         if (this->disable_physics_updates_)
00384           this->world_->EnablePhysicsEngine(this->physics_engine_enabled_);
00385       }
00386     }
00387   }
00388 }
00389 
00391 // Put laser data to the interface
00392 void GazeboRosJointPoseTrajectory::QueueThread()
00393 {
00394   static const double timeout = 0.01;
00395   while (this->rosnode_->ok())
00396   {
00397     this->queue_.callAvailable(ros::WallDuration(timeout));
00398   }
00399 }
00400 }


gazebo_plugins
Author(s): John Hsu
autogenerated on Fri Aug 28 2015 10:47:25