38 ROS_WARN_NAMED(
"gazebo_ros_joint_trajectory",
"DEPRECATED: gazebo_ros_joint_trajectory has been renamed to gazebo_ros_joint_pose_trajectory");
74 if (this->
sdf->HasElement(
"robotNamespace"))
77 if (!this->
sdf->HasElement(
"serviceName"))
85 if (!this->
sdf->HasElement(
"topicName"))
93 if (!this->
sdf->HasElement(
"updateRate"))
95 ROS_INFO_NAMED(
"joint_trajectory",
"joint trajectory plugin missing <updateRate>, defaults" 96 " to 0.0 (as fast as possible)");
110 gzerr <<
"Not loading plugin since ROS hasn't been " 111 <<
"properly initialized. Try starting gazebo with ros plugin:\n" 112 <<
" gazebo -s libgazebo_ros_api_plugin.so\n";
129 ros::SubscribeOptions::create<trajectory_msgs::JointTrajectory>(
136 #ifdef ENABLE_SERVICE 140 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointTrajectory>(
148 #if GAZEBO_MAJOR_VERSION >= 8 168 const trajectory_msgs::JointTrajectory::ConstPtr& trajectory)
179 physics::EntityPtr ent =
180 #if GAZEBO_MAJOR_VERSION >= 8 186 this->
reference_link_ = boost::dynamic_pointer_cast<physics::Link>(ent);
189 ROS_ERROR_NAMED(
"joint_trajectory",
"ros_joint_trajectory plugin needs a reference link [%s] as" 196 ROS_DEBUG_NAMED(
"joint_trajectory",
"test: update model pose by keeping link [%s] stationary" 202 unsigned int chain_size = trajectory->joint_names.size();
203 this->
joints_.resize(chain_size);
204 for (
unsigned int i = 0; i < chain_size; ++i)
206 this->
joints_[i] = this->
model_->GetJoint(trajectory->joint_names[i]);
209 unsigned int points_size = trajectory->points.size();
210 this->
points_.resize(points_size);
211 for (
unsigned int i = 0; i < points_size; ++i)
213 this->
points_[i].positions.resize(chain_size);
214 this->
points_[i].time_from_start = trajectory->points[i].time_from_start;
215 for (
unsigned int j = 0; j < chain_size; ++j)
217 this->
points_[i].positions[j] = trajectory->points[i].positions[j];
223 trajectory->header.stamp.nsec);
224 #if GAZEBO_MAJOR_VERSION >= 8 225 common::Time cur_time = this->
world_->SimTime();
227 common::Time cur_time = this->
world_->GetSimTime();
239 #if GAZEBO_MAJOR_VERSION >= 8 241 this->
world_->SetPhysicsEnabled(
false);
244 this->
world_->EnablePhysicsEngine(
false);
249 #ifdef ENABLE_SERVICE 251 const gazebo_msgs::SetJointTrajectory::Request& req,
252 const gazebo_msgs::SetJointTrajectory::Response& res)
266 physics::EntityPtr ent =
267 #if GAZEBO_MAJOR_VERSION >= 8 273 this->
reference_link_ = boost::shared_dynamic_cast<physics::Link>(ent);
276 ROS_ERROR_NAMED(
"joint_trajectory",
"ros_joint_trajectory plugin specified a reference link [%s]" 277 " that does not exist, aborting.\n",
279 ROS_DEBUG_NAMED(
"joint_trajectory",
"will set model [%s] configuration, keeping model root link" 280 " stationary.", this->
model_->GetName().c_str());
284 ROS_DEBUG_NAMED(
"joint_trajectory",
"test: update model pose by keeping link [%s] stationary" 288 #if GAZEBO_MAJOR_VERSION >= 8 289 this->
model_ = this->
world_->ModelByName(req.model_name);
291 this->model_ = this->
world_->GetModel(req.model_name);
298 ROS_INFO_NAMED(
"joint_trajectory",
"found model[%s] by link name specified in frame_id[%s]",
299 this->model_->GetName().c_str(),
300 req.joint_trajectory.header.frame_id.c_str());
304 ROS_WARN_NAMED(
"joint_trajectory",
"no model found by link name specified in frame_id[%s]," 305 " aborting.", req.joint_trajectory.header.frame_id.c_str());
315 req.joint_trajectory.header.stamp.sec,
316 req.joint_trajectory.header.stamp.nsec);
325 #if GAZEBO_MAJOR_VERSION >= 8 327 this->
world_->SetPhysicsEnabled(
false);
330 this->
world_->EnablePhysicsEngine(
false);
345 #if GAZEBO_MAJOR_VERSION >= 8 346 common::Time cur_time = this->
world_->SimTime();
348 common::Time cur_time = this->
world_->GetSimTime();
358 if (this->trajectory_index < this->
points_.size())
360 ROS_INFO_NAMED(
"joint_trajectory",
"time [%f] updating configuration [%d/%lu]",
364 #if GAZEBO_MAJOR_VERSION >= 8 365 ignition::math::Pose3d reference_pose = this->
model_->WorldPose();
367 ignition::math::Pose3d reference_pose = this->
model_->GetWorldPose().Ign();
371 #if GAZEBO_MAJOR_VERSION >= 8 380 unsigned int chain_size = this->
joints_.size();
384 for (
unsigned int i = 0; i < chain_size; ++i)
389 #if GAZEBO_MAJOR_VERSION >= 9 390 this->
joints_[i]->SetPosition(0,
393 this->
joints_[i]->SetPosition(0,
401 this->
model_->SetLinkWorldPose(reference_pose,
404 this->
model_->SetWorldPose(reference_pose);
408 ROS_ERROR_NAMED(
"joint_trajectory",
"point[%u] in JointTrajectory has different number of" 409 " joint names[%u] and positions[%lu].",
415 gazebo::common::Time duration(
417 this->points_[this->trajectory_index].time_from_start.nsec);
421 this->trajectory_index++;
433 #if GAZEBO_MAJOR_VERSION >= 8 448 static const double timeout = 0.01;
common::Time last_time_
save last_time
std::string service_name_
unsigned int trajectory_index
virtual ~GazeboRosJointTrajectory()
Destructor.
boost::thread deferred_load_thread_
bool physics_engine_enabled_
#define ROS_INFO_NAMED(name,...)
boost::thread callback_queue_thread_
boost::mutex update_mutex
A mutex to lock access to fields that are used in message callbacks.
event::ConnectionPtr update_connection_
trajectory_msgs::JointTrajectory joint_trajectory_
#define ROS_WARN_NAMED(name,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL bool isInitialized()
ros::CallbackQueue queue_
GazeboRosJointTrajectory()
Constructor.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
common::Time trajectory_start
std::vector< trajectory_msgs::JointTrajectoryPoint > points_
std::string robot_namespace_
for setting ROS name space
#define ROS_DEBUG_NAMED(name,...)
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
physics::LinkPtr reference_link_
pose should be set relative to this link (default to "world")
void SetTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &trajectory)
Update the controller.
bool getParam(const std::string &key, std::string &s) const
ros::NodeHandle * rosnode_
pointer to ros node
#define ROS_ERROR_NAMED(name,...)
std::string reference_link_name_
boost::shared_ptr< void > VoidPtr
std::string topic_name_
topic name
std::vector< gazebo::physics::JointPtr > joints_
bool disable_physics_updates_
geometry_msgs::Pose model_pose_
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the controller.