gazebo_ros_joint_pose_trajectory.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 /*
19  * Desc: 3D position interface for ground truth.
20  * Author: Sachin Chitta and John Hsu
21  * Date: 1 June 2008
22  */
23 
24 #include <string>
25 #include <stdlib.h>
26 #include <tf/tf.h>
27 
29 
30 #ifdef ENABLE_PROFILER
31 #include <ignition/common/Profiler.hh>
32 #endif
33 
34 namespace gazebo
35 {
36 GZ_REGISTER_MODEL_PLUGIN(GazeboRosJointPoseTrajectory);
37 
39 // Constructor
40 ROS_DEPRECATED GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory() // replaced with GazeboROSJointPoseTrajectory
41 {
42 
43  this->has_trajectory_ = false;
44  this->trajectory_index = 0;
45  this->joint_trajectory_.points.clear();
46  this->physics_engine_enabled_ = true;
47  this->disable_physics_updates_ = true;
48 }
49 
51 // Destructor
53 {
54  this->update_connection_.reset();
55  // Finalize the controller
56  this->rosnode_->shutdown();
57  this->queue_.clear();
58  this->queue_.disable();
59  this->callback_queue_thread_.join();
60  delete this->rosnode_;
61 }
62 
64 // Load the controller
65 void GazeboRosJointPoseTrajectory::Load(physics::ModelPtr _model,
66  sdf::ElementPtr _sdf)
67 {
68  // save pointers
69  this->model_ = _model;
70  this->sdf = _sdf;
71  this->world_ = this->model_->GetWorld();
72 
73  // this->world_->SetGravity(ignition::math::Vector3d(0, 0, 0));
74 
75  // load parameters
76  this->robot_namespace_ = "";
77  if (this->sdf->HasElement("robotNamespace"))
78  this->robot_namespace_ = this->sdf->Get<std::string>("robotNamespace") + "/";
79 
80  if (!this->sdf->HasElement("serviceName"))
81  {
82  // default
83  this->service_name_ = "set_joint_trajectory";
84  }
85  else
86  this->service_name_ = this->sdf->Get<std::string>("serviceName");
87 
88  if (!this->sdf->HasElement("topicName"))
89  {
90  // default
91  this->topic_name_ = "set_joint_trajectory";
92  }
93  else
94  this->topic_name_ = this->sdf->Get<std::string>("topicName");
95 
96  if (!this->sdf->HasElement("updateRate"))
97  {
98  ROS_INFO_NAMED("joint_pose_trajectory", "joint trajectory plugin missing <updateRate>, defaults"
99  " to 0.0 (as fast as possible)");
100  this->update_rate_ = 0;
101  }
102  else
103  this->update_rate_ = this->sdf->Get<double>("updateRate");
104 
105  // Make sure the ROS node for Gazebo has already been initialized
106  if (!ros::isInitialized())
107  {
108  ROS_FATAL_STREAM_NAMED("joint_pose_trajectory", "A ROS node for Gazebo has not been initialized, unable to load plugin. "
109  << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
110  return;
111  }
112 
113  this->deferred_load_thread_ = boost::thread(
114  boost::bind(&GazeboRosJointPoseTrajectory::LoadThread, this));
115 
116 }
117 
119 // Load the controller
121 {
122  this->rosnode_ = new ros::NodeHandle(this->robot_namespace_);
123 
124  // resolve tf prefix
125  std::string prefix;
126  this->rosnode_->getParam(std::string("tf_prefix"), prefix);
127 
128  if (this->topic_name_ != "")
129  {
130  ros::SubscribeOptions trajectory_so =
131  ros::SubscribeOptions::create<trajectory_msgs::JointTrajectory>(
132  this->topic_name_, 100, boost::bind(
134  ros::VoidPtr(), &this->queue_);
135  this->sub_ = this->rosnode_->subscribe(trajectory_so);
136  }
137 
138 #ifdef ENABLE_SERVICE
139  if (this->service_name_ != "")
140  {
142  ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointTrajectory>(
143  this->service_name_,
144  boost::bind(&GazeboRosJointPoseTrajectory::SetTrajectory, this, _1, _2),
145  ros::VoidPtr(), &this->queue_);
146  this->srv_ = this->rosnode_->advertiseService(srv_aso);
147  }
148 #endif
149 
150 #if GAZEBO_MAJOR_VERSION >= 8
151  this->last_time_ = this->world_->SimTime();
152 #else
153  this->last_time_ = this->world_->GetSimTime();
154 #endif
155 
156  // start custom queue for joint trajectory plugin ros topics
157  this->callback_queue_thread_ =
158  boost::thread(boost::bind(&GazeboRosJointPoseTrajectory::QueueThread, this));
159 
160  // New Mechanism for Updating every World Cycle
161  // Listen to the update event. This event is broadcast every
162  // simulation iteration.
163  this->update_connection_ = event::Events::ConnectWorldUpdateBegin(
164  boost::bind(&GazeboRosJointPoseTrajectory::UpdateStates, this));
165 }
166 
168 // set joint trajectory
170  const trajectory_msgs::JointTrajectory::ConstPtr& trajectory)
171 {
172  boost::mutex::scoped_lock lock(this->update_mutex);
173 
174  this->reference_link_name_ = trajectory->header.frame_id;
175  // do this every time a new joint trajectory is supplied,
176  // use header.frame_id as the reference_link_name_
177  if (this->reference_link_name_ != "world" &&
178  this->reference_link_name_ != "/map" &&
179  this->reference_link_name_ != "map")
180  {
181  physics::EntityPtr ent =
182 #if GAZEBO_MAJOR_VERSION >= 8
183  this->world_->EntityByName(this->reference_link_name_);
184 #else
185  this->world_->GetEntity(this->reference_link_name_);
186 #endif
187  if (ent)
188  this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
189  if (!this->reference_link_)
190  {
191  ROS_ERROR_NAMED("joint_pose_trajectory", "ros_joint_trajectory plugin needs a reference link [%s] as"
192  " frame_id, aborting.\n", this->reference_link_name_.c_str());
193  return;
194  }
195  else
196  {
197  this->model_ = this->reference_link_->GetParentModel();
198  ROS_DEBUG_NAMED("joint_pose_trajectory", "test: update model pose by keeping link [%s] stationary"
199  " inertially", this->reference_link_->GetName().c_str());
200  }
201  }
202 
203  // copy joint configuration into a map
204  unsigned int chain_size = trajectory->joint_names.size();
205  this->joints_.resize(chain_size);
206  for (unsigned int i = 0; i < chain_size; ++i)
207  {
208  this->joints_[i] = this->model_->GetJoint(trajectory->joint_names[i]);
209  }
210 
211  unsigned int points_size = trajectory->points.size();
212  this->points_.resize(points_size);
213  for (unsigned int i = 0; i < points_size; ++i)
214  {
215  this->points_[i].positions.resize(chain_size);
216  this->points_[i].time_from_start = trajectory->points[i].time_from_start;
217  for (unsigned int j = 0; j < chain_size; ++j)
218  {
219  this->points_[i].positions[j] = trajectory->points[i].positions[j];
220  }
221  }
222 
223  // trajectory start time
224  this->trajectory_start = gazebo::common::Time(trajectory->header.stamp.sec,
225  trajectory->header.stamp.nsec);
226 #if GAZEBO_MAJOR_VERSION >= 8
227  common::Time cur_time = this->world_->SimTime();
228 #else
229  common::Time cur_time = this->world_->GetSimTime();
230 #endif
231  if (this->trajectory_start < cur_time)
232  this->trajectory_start = cur_time;
233 
234  // update the joint trajectory to play
235  this->has_trajectory_ = true;
236  // reset trajectory_index to beginning of new trajectory
237  this->trajectory_index = 0;
238 
239  if (this->disable_physics_updates_)
240  {
241 #if GAZEBO_MAJOR_VERSION >= 8
242  this->physics_engine_enabled_ = this->world_->PhysicsEnabled();
243  this->world_->SetPhysicsEnabled(false);
244 #else
245  this->physics_engine_enabled_ = this->world_->GetEnablePhysicsEngine();
246  this->world_->EnablePhysicsEngine(false);
247 #endif
248  }
249 }
250 
251 #ifdef ENABLE_SERVICE
253  const gazebo_msgs::SetJointTrajectory::Request& req,
254  const gazebo_msgs::SetJointTrajectory::Response& res)
255 {
256  boost::mutex::scoped_lock lock(this->update_mutex);
257 
258  this->model_pose_ = req.model_pose;
259  this->set_model_pose_ = req.set_model_pose;
260 
261  this->reference_link_name_ = req.joint_trajectory.header.frame_id;
262  // do this every time a new joint_trajectory is supplied,
263  // use header.frame_id as the reference_link_name_
264  if (this->reference_link_name_ != "world" &&
265  this->reference_link_name_ != "/map" &&
266  this->reference_link_name_ != "map")
267  {
268  physics::EntityPtr ent =
269 #if GAZEBO_MAJOR_VERSION >= 8
270  this->world_->EntityByName(this->reference_link_name_);
271 #else
272  this->world_->GetEntity(this->reference_link_name_);
273 #endif
274  if (ent)
275  this->reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
276  if (!this->reference_link_)
277  {
278  ROS_ERROR_NAMED("joint_pose_trajectory", "ros_joint_trajectory plugin specified a reference link [%s]"
279  " that does not exist, aborting.\n",
280  this->reference_link_name_.c_str());
281  ROS_DEBUG_NAMED("joint_pose_trajectory", "will set model [%s] configuration, keeping model root link"
282  " stationary.", this->model_->GetName().c_str());
283  return false;
284  }
285  else
286  ROS_DEBUG_NAMED("joint_pose_trajectory", "test: update model pose by keeping link [%s] stationary"
287  " inertially", this->reference_link_->GetName().c_str());
288  }
289 
290 #if GAZEBO_MAJOR_VERSION >= 8
291  this->model_ = this->world_->ModelByName(req.model_name);
292 #else
293  this->model_ = this->world_->GetModel(req.model_name);
294 #endif
295  if (!this->model_) // look for it by frame_id name
296  {
297  this->model_ = this->reference_link_->GetParentModel();
298  if (this->model_)
299  {
300  ROS_INFO_NAMED("joint_pose_trajectory", "found model[%s] by link name specified in frame_id[%s]",
301  this->model_->GetName().c_str(),
302  req.joint_trajectory.header.frame_id.c_str());
303  }
304  else
305  {
306  ROS_WARN_NAMED("joint_pose_trajectory", "no model found by link name specified in frame_id[%s],"
307  " aborting.", req.joint_trajectory.header.frame_id.c_str());
308  return false;
309  }
310  }
311 
312  // copy joint configuration into a map
313  this->joint_trajectory_ = req.joint_trajectory;
314 
315  // trajectory start time
316  this->trajectory_start = gazebo::common::Time(
317  req.joint_trajectory.header.stamp.sec,
318  req.joint_trajectory.header.stamp.nsec);
319 
320  // update the joint_trajectory to play
321  this->has_trajectory_ = true;
322  // reset trajectory_index to beginning of new trajectory
323  this->trajectory_index = 0;
324  this->disable_physics_updates_ = req.disable_physics_updates;
325  if (this->disable_physics_updates_)
326  {
327 #if GAZEBO_MAJOR_VERSION >= 8
328  this->physics_engine_enabled_ = this->world_->PhysicsEnabled();
329  this->world_->SetPhysicsEnabled(false);
330 #else
331  this->physics_engine_enabled_ = this->world_->GetEnablePhysicsEngine();
332  this->world_->EnablePhysicsEngine(false);
333 #endif
334  }
335 
336  return true;
337 }
338 #endif
339 
341 // Play the trajectory, update states
343 {
344 #ifdef ENABLE_PROFILER
345  IGN_PROFILE("GazeboRosJointPoseTrajectory::UpdateStates");
346 
347  IGN_PROFILE_BEGIN("update");
348 #endif
349  boost::mutex::scoped_lock lock(this->update_mutex);
350  if (this->has_trajectory_)
351  {
352 #if GAZEBO_MAJOR_VERSION >= 8
353  common::Time cur_time = this->world_->SimTime();
354 #else
355  common::Time cur_time = this->world_->GetSimTime();
356 #endif
357  // roll out trajectory via set model configuration
358  // gzerr << "i[" << trajectory_index << "] time "
359  // << trajectory_start << " now: " << cur_time << " : "<< "\n";
360  if (cur_time >= this->trajectory_start)
361  {
362  // @todo: consider a while loop until the trajectory
363  // catches up to the current time
364  // gzerr << trajectory_index << " : " << this->points_.size() << "\n";
365  if (this->trajectory_index < this->points_.size())
366  {
367  ROS_INFO_NAMED("joint_pose_trajectory", "time [%f] updating configuration [%d/%lu]",
368  cur_time.Double(), this->trajectory_index, this->points_.size());
369 
370  // get reference link pose before updates
371 #if GAZEBO_MAJOR_VERSION >= 8
372  ignition::math::Pose3d reference_pose = this->model_->WorldPose();
373 #else
374  ignition::math::Pose3d reference_pose = this->model_->GetWorldPose().Ign();
375 #endif
376  if (this->reference_link_)
377  {
378 #if GAZEBO_MAJOR_VERSION >= 8
379  reference_pose = this->reference_link_->WorldPose();
380 #else
381  reference_pose = this->reference_link_->GetWorldPose().Ign();
382 #endif
383  }
384 
385  // trajectory roll-out based on time:
386  // set model configuration from trajectory message
387  unsigned int chain_size = this->joints_.size();
388  if (chain_size ==
389  this->points_[this->trajectory_index].positions.size())
390  {
391  for (unsigned int i = 0; i < chain_size; ++i)
392  {
393  // this is not the most efficient way to set things
394  if (this->joints_[i])
395  {
396 #if GAZEBO_MAJOR_VERSION >= 9
397  this->joints_[i]->SetPosition(0,
398  this->points_[this->trajectory_index].positions[i], true);
399 #else
400  this->joints_[i]->SetPosition(0,
401  this->points_[this->trajectory_index].positions[i]);
402 #endif
403  }
404  }
405 
406  // set model pose
407  if (this->reference_link_)
408  this->model_->SetLinkWorldPose(reference_pose,
409  this->reference_link_);
410  else
411  this->model_->SetWorldPose(reference_pose);
412  }
413  else
414  {
415  ROS_ERROR_NAMED("joint_pose_trajectory", "point[%u] in JointTrajectory has different number of"
416  " joint names[%u] and positions[%lu].",
417  this->trajectory_index, chain_size,
418  this->points_[this->trajectory_index].positions.size());
419  }
420 
421  // this->world_->SetPaused(is_paused); // resume original pause-state
422  gazebo::common::Time duration(
423  this->points_[this->trajectory_index].time_from_start.sec,
424  this->points_[this->trajectory_index].time_from_start.nsec);
425 
426  // reset start time for next trajectory point
427  this->trajectory_start += duration;
428  this->trajectory_index++; // increment to next trajectory point
429 
430  // save last update time stamp
431  this->last_time_ = cur_time;
432  }
433  else // no more trajectory points
434  {
435  // trajectory finished
436  this->reference_link_.reset();
437  this->has_trajectory_ = false;
438  if (this->disable_physics_updates_)
439  {
440 #if GAZEBO_MAJOR_VERSION >= 8
441  this->world_->SetPhysicsEnabled(this->physics_engine_enabled_);
442 #else
443  this->world_->EnablePhysicsEngine(this->physics_engine_enabled_);
444 #endif
445  }
446  }
447  }
448  }
449 #ifdef ENABLE_PROFILER
450  IGN_PROFILE_END();
451 #endif
452 }
453 
455 // Put laser data to the interface
457 {
458  static const double timeout = 0.01;
459  while (this->rosnode_->ok())
460  {
461  this->queue_.callAvailable(ros::WallDuration(timeout));
462  }
463 }
464 }
gazebo::GazeboRosJointPoseTrajectory::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_joint_pose_trajectory.h:123
gazebo::GazeboRosJointPoseTrajectory::model_
physics::ModelPtr model_
Definition: gazebo_ros_joint_pose_trajectory.h:75
boost::shared_ptr< void >
gazebo
gazebo::GazeboRosJointPoseTrajectory::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_joint_pose_trajectory.h:115
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
gazebo::GazeboRosJointPoseTrajectory::joints_
std::vector< gazebo::physics::JointPtr > joints_
Definition: gazebo_ros_joint_pose_trajectory.h:119
ros::CallbackQueue::clear
void clear()
gazebo::GazeboRosJointPoseTrajectory::disable_physics_updates_
bool disable_physics_updates_
Definition: gazebo_ros_joint_pose_trajectory.h:109
gazebo_ros_joint_pose_trajectory.h
gazebo::GazeboRosJointPoseTrajectory::sub_
ros::Subscriber sub_
Definition: gazebo_ros_joint_pose_trajectory.h:83
gazebo::GazeboRosJointPoseTrajectory::service_name_
std::string service_name_
Definition: gazebo_ros_joint_pose_trajectory.h:94
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
gazebo::GazeboRosJointPoseTrajectory::physics_engine_enabled_
bool physics_engine_enabled_
Definition: gazebo_ros_joint_pose_trajectory.h:110
ROS_DEPRECATED
#define ROS_DEPRECATED
gazebo::GazeboRosJointPoseTrajectory::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_joint_pose_trajectory.h:82
gazebo::GazeboRosJointPoseTrajectory::set_model_pose_
bool set_model_pose_
Definition: gazebo_ros_joint_pose_trajectory.h:89
gazebo::GazeboRosJointPoseTrajectory::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_joint_pose_trajectory.h:117
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
gazebo::GazeboRosJointPoseTrajectory::SetTrajectory
void SetTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &trajectory)
Update the controller.
Definition: gazebo_ros_joint_pose_trajectory.cpp:169
gazebo::GZ_REGISTER_MODEL_PLUGIN
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
gazebo::GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory
GazeboRosJointPoseTrajectory()
Constructor.
Definition: gazebo_ros_joint_pose_trajectory.cpp:40
gazebo::GazeboRosJointPoseTrajectory::joint_trajectory_
trajectory_msgs::JointTrajectory joint_trajectory_
Definition: gazebo_ros_joint_pose_trajectory.h:125
gazebo::GazeboRosJointPoseTrajectory::srv_
ros::ServiceServer srv_
Definition: gazebo_ros_joint_pose_trajectory.h:84
ros::isInitialized
ROSCPP_DECL bool isInitialized()
gazebo::GazeboRosJointPoseTrajectory::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_joint_pose_trajectory.h:93
gazebo::GazeboRosJointPoseTrajectory::model_pose_
geometry_msgs::Pose model_pose_
Definition: gazebo_ros_joint_pose_trajectory.h:90
gazebo::GazeboRosJointPoseTrajectory::trajectory_index
unsigned int trajectory_index
Definition: gazebo_ros_joint_pose_trajectory.h:105
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::AdvertiseServiceOptions
gazebo::GazeboRosJointPoseTrajectory::QueueThread
void QueueThread()
Definition: gazebo_ros_joint_pose_trajectory.cpp:456
gazebo::GazeboRosJointPoseTrajectory::update_rate_
double update_rate_
Definition: gazebo_ros_joint_pose_trajectory.h:108
gazebo::GazeboRosJointPoseTrajectory::LoadThread
void LoadThread()
Definition: gazebo_ros_joint_pose_trajectory.cpp:120
gazebo::GazeboRosJointPoseTrajectory::has_trajectory_
bool has_trajectory_
Definition: gazebo_ros_joint_pose_trajectory.h:85
gazebo::GazeboRosJointPoseTrajectory::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_joint_pose_trajectory.h:128
gazebo::GazeboRosJointPoseTrajectory::Load
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_joint_pose_trajectory.cpp:65
tf.h
ros::NodeHandle::ok
bool ok() const
gazebo::GazeboRosJointPoseTrajectory::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_joint_pose_trajectory.h:113
ros::SubscribeOptions
gazebo::GazeboRosJointPoseTrajectory::world_
physics::WorldPtr world_
Definition: gazebo_ros_joint_pose_trajectory.h:74
gazebo::GazeboRosJointPoseTrajectory::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_joint_pose_trajectory.h:130
gazebo::GazeboRosJointPoseTrajectory::reference_link_
physics::LinkPtr reference_link_
pose should be set relative to this link (default to "world")
Definition: gazebo_ros_joint_pose_trajectory.h:78
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosJointPoseTrajectory::~GazeboRosJointPoseTrajectory
virtual ~GazeboRosJointPoseTrajectory()
Destructor.
Definition: gazebo_ros_joint_pose_trajectory.cpp:52
gazebo::GazeboRosJointPoseTrajectory::trajectory_start
common::Time trajectory_start
Definition: gazebo_ros_joint_pose_trajectory.h:104
gazebo::GazeboRosJointPoseTrajectory::update_mutex
boost::mutex update_mutex
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_joint_pose_trajectory.h:98
ros::WallDuration
gazebo::GazeboRosJointPoseTrajectory::last_time_
common::Time last_time_
save last_time
Definition: gazebo_ros_joint_pose_trajectory.h:101
gazebo::GazeboRosJointPoseTrajectory::points_
std::vector< trajectory_msgs::JointTrajectoryPoint > points_
Definition: gazebo_ros_joint_pose_trajectory.h:120
ros::NodeHandle::shutdown
void shutdown()
gazebo::GazeboRosJointPoseTrajectory::reference_link_name_
std::string reference_link_name_
Definition: gazebo_ros_joint_pose_trajectory.h:79
ros::CallbackQueue::callAvailable
void callAvailable()
gazebo::GazeboRosJointPoseTrajectory::UpdateStates
void UpdateStates()
Definition: gazebo_ros_joint_pose_trajectory.cpp:342
ros::CallbackQueue::disable
void disable()
ros::NodeHandle


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