30 #ifdef ENABLE_PROFILER
31 #include <ignition/common/Profiler.hh>
77 if (this->
sdf->HasElement(
"robotNamespace"))
80 if (!this->
sdf->HasElement(
"serviceName"))
88 if (!this->
sdf->HasElement(
"topicName"))
96 if (!this->
sdf->HasElement(
"updateRate"))
98 ROS_INFO_NAMED(
"joint_pose_trajectory",
"joint trajectory plugin missing <updateRate>, defaults"
99 " to 0.0 (as fast as possible)");
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)");
131 ros::SubscribeOptions::create<trajectory_msgs::JointTrajectory>(
138 #ifdef ENABLE_SERVICE
142 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointTrajectory>(
150 #if GAZEBO_MAJOR_VERSION >= 8
170 const trajectory_msgs::JointTrajectory::ConstPtr& trajectory)
181 physics::EntityPtr ent =
182 #if GAZEBO_MAJOR_VERSION >= 8
188 this->
reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
191 ROS_ERROR_NAMED(
"joint_pose_trajectory",
"ros_joint_trajectory plugin needs a reference link [%s] as"
198 ROS_DEBUG_NAMED(
"joint_pose_trajectory",
"test: update model pose by keeping link [%s] stationary"
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)
208 this->
joints_[i] = this->
model_->GetJoint(trajectory->joint_names[i]);
211 unsigned int points_size = trajectory->points.size();
212 this->
points_.resize(points_size);
213 for (
unsigned int i = 0; i < points_size; ++i)
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)
219 this->
points_[i].positions[j] = trajectory->points[i].positions[j];
225 trajectory->header.stamp.nsec);
226 #if GAZEBO_MAJOR_VERSION >= 8
227 common::Time cur_time = this->
world_->SimTime();
229 common::Time cur_time = this->
world_->GetSimTime();
241 #if GAZEBO_MAJOR_VERSION >= 8
243 this->
world_->SetPhysicsEnabled(
false);
246 this->
world_->EnablePhysicsEngine(
false);
251 #ifdef ENABLE_SERVICE
253 const gazebo_msgs::SetJointTrajectory::Request& req,
254 const gazebo_msgs::SetJointTrajectory::Response& res)
268 physics::EntityPtr ent =
269 #if GAZEBO_MAJOR_VERSION >= 8
275 this->
reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
278 ROS_ERROR_NAMED(
"joint_pose_trajectory",
"ros_joint_trajectory plugin specified a reference link [%s]"
279 " that does not exist, aborting.\n",
281 ROS_DEBUG_NAMED(
"joint_pose_trajectory",
"will set model [%s] configuration, keeping model root link"
282 " stationary.", this->
model_->GetName().c_str());
286 ROS_DEBUG_NAMED(
"joint_pose_trajectory",
"test: update model pose by keeping link [%s] stationary"
290 #if GAZEBO_MAJOR_VERSION >= 8
291 this->
model_ = this->
world_->ModelByName(req.model_name);
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());
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());
317 req.joint_trajectory.header.stamp.sec,
318 req.joint_trajectory.header.stamp.nsec);
327 #if GAZEBO_MAJOR_VERSION >= 8
329 this->
world_->SetPhysicsEnabled(
false);
332 this->
world_->EnablePhysicsEngine(
false);
344 #ifdef ENABLE_PROFILER
345 IGN_PROFILE(
"GazeboRosJointPoseTrajectory::UpdateStates");
347 IGN_PROFILE_BEGIN(
"update");
352 #if GAZEBO_MAJOR_VERSION >= 8
353 common::Time cur_time = this->
world_->SimTime();
355 common::Time cur_time = this->
world_->GetSimTime();
365 if (this->trajectory_index < this->
points_.size())
367 ROS_INFO_NAMED(
"joint_pose_trajectory",
"time [%f] updating configuration [%d/%lu]",
368 cur_time.Double(), this->trajectory_index, this->points_.size());
371 #if GAZEBO_MAJOR_VERSION >= 8
372 ignition::math::Pose3d reference_pose = this->
model_->WorldPose();
374 ignition::math::Pose3d reference_pose = this->
model_->GetWorldPose().Ign();
378 #if GAZEBO_MAJOR_VERSION >= 8
387 unsigned int chain_size = this->
joints_.size();
391 for (
unsigned int i = 0; i < chain_size; ++i)
396 #if GAZEBO_MAJOR_VERSION >= 9
397 this->
joints_[i]->SetPosition(0,
400 this->
joints_[i]->SetPosition(0,
408 this->
model_->SetLinkWorldPose(reference_pose,
411 this->
model_->SetWorldPose(reference_pose);
415 ROS_ERROR_NAMED(
"joint_pose_trajectory",
"point[%u] in JointTrajectory has different number of"
416 " joint names[%u] and positions[%lu].",
422 gazebo::common::Time duration(
424 this->points_[this->trajectory_index].time_from_start.nsec);
428 this->trajectory_index++;
440 #if GAZEBO_MAJOR_VERSION >= 8
449 #ifdef ENABLE_PROFILER
458 static const double timeout = 0.01;