gazebo_ros_joint_state_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Markus Bader <markus.bader@tuwien.ac.at>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the <organization> nor the
13  * names of its contributors may be used to endorse or promote products
14  * derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
17  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  * DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
20  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  *
27  **/
28 #include <boost/algorithm/string.hpp>
30 #ifdef ENABLE_PROFILER
31 #include <ignition/common/Profiler.hh>
32 #endif
34 #include <tf/transform_listener.h>
35 
36 using namespace gazebo;
37 
39 
40 // Destructor
42  rosnode_->shutdown();
43 }
44 
45 void GazeboRosJointStatePublisher::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf ) {
46  // Store the pointer to the model
47  this->parent_ = _parent;
48  this->world_ = _parent->GetWorld();
49 
50  this->robot_namespace_ = parent_->GetName ();
51  if ( !_sdf->HasElement ( "robotNamespace" ) ) {
52  ROS_INFO_NAMED("joint_state_publisher", "GazeboRosJointStatePublisher Plugin missing <robotNamespace>, defaults to \"%s\"",
53  this->robot_namespace_.c_str() );
54  } else {
55  this->robot_namespace_ = _sdf->GetElement ( "robotNamespace" )->Get<std::string>();
56  if ( this->robot_namespace_.empty() ) this->robot_namespace_ = parent_->GetName ();
57  }
58  if ( !robot_namespace_.empty() ) this->robot_namespace_ += "/";
60 
61  if ( !_sdf->HasElement ( "jointName" ) ) {
62  ROS_ASSERT ( "GazeboRosJointStatePublisher Plugin missing jointNames" );
63  } else {
64  sdf::ElementPtr element = _sdf->GetElement ( "jointName" ) ;
65  std::string joint_names = element->Get<std::string>();
66  boost::erase_all ( joint_names, " " );
67  boost::split ( joint_names_, joint_names, boost::is_any_of ( "," ) );
68  }
69 
70  this->update_rate_ = 100.0;
71  if ( !_sdf->HasElement ( "updateRate" ) ) {
72  ROS_WARN_NAMED("joint_state_publisher", "GazeboRosJointStatePublisher Plugin (ns = %s) missing <updateRate>, defaults to %f",
73  this->robot_namespace_.c_str(), this->update_rate_ );
74  } else {
75  this->update_rate_ = _sdf->GetElement ( "updateRate" )->Get<double>();
76  }
77 
78  // Initialize update rate stuff
79  if ( this->update_rate_ > 0.0 ) {
80  this->update_period_ = 1.0 / this->update_rate_;
81  } else {
82  this->update_period_ = 0.0;
83  }
84 #if GAZEBO_MAJOR_VERSION >= 8
85  last_update_time_ = this->world_->SimTime();
86 #else
87  last_update_time_ = this->world_->GetSimTime();
88 #endif
89 
90  for ( unsigned int i = 0; i< joint_names_.size(); i++ ) {
91  physics::JointPtr joint = this->parent_->GetJoint(joint_names_[i]);
92  if (!joint) {
93  ROS_FATAL_NAMED("joint_state_publisher", "Joint %s does not exist!", joint_names_[i].c_str());
94  }
95  joints_.push_back ( joint );
96  ROS_INFO_NAMED("joint_state_publisher", "GazeboRosJointStatePublisher is going to publish joint: %s", joint_names_[i].c_str() );
97  }
98 
99  ROS_INFO_NAMED("joint_state_publisher", "Starting GazeboRosJointStatePublisher Plugin (ns = %s)!, parent name: %s", this->robot_namespace_.c_str(), parent_->GetName ().c_str() );
100 
102  joint_state_publisher_ = rosnode_->advertise<sensor_msgs::JointState> ( "joint_states",1000 );
103 
104 #if GAZEBO_MAJOR_VERSION >= 8
105  last_update_time_ = this->world_->SimTime();
106 #else
107  last_update_time_ = this->world_->GetSimTime();
108 #endif
109  // Listen to the update event. This event is broadcast every
110  // simulation iteration.
111  this->updateConnection = event::Events::ConnectWorldUpdateBegin (
112  boost::bind ( &GazeboRosJointStatePublisher::OnUpdate, this, _1 ) );
113 }
114 
115 void GazeboRosJointStatePublisher::OnUpdate ( const common::UpdateInfo & _info )
116 {
117 #ifdef ENABLE_PROFILER
118  IGN_PROFILE("GazeboRosCamera::OnNewFrame");
119 #endif
120  // Apply a small linear velocity to the model.
121 #if GAZEBO_MAJOR_VERSION >= 8
122  common::Time current_time = this->world_->SimTime();
123 #else
124  common::Time current_time = this->world_->GetSimTime();
125 #endif
126  if (current_time < last_update_time_)
127  {
128  ROS_WARN_NAMED("joint_state_publisher", "Negative joint state update time difference detected.");
129  last_update_time_ = current_time;
130  }
131 
132  double seconds_since_last_update = ( current_time - last_update_time_ ).Double();
133 
134  if ( seconds_since_last_update > update_period_ ) {
135 #ifdef ENABLE_PROFILER
136  IGN_PROFILE_BEGIN("publishJointStates");
137 #endif
139 #ifdef ENABLE_PROFILER
140  IGN_PROFILE_END();
141 #endif
142  last_update_time_+= common::Time ( update_period_ );
143  }
144 
145 }
146 
148  ros::Time current_time = ros::Time::now();
149 
150  joint_state_.header.stamp = current_time;
151  joint_state_.name.resize ( joints_.size() );
152  joint_state_.position.resize ( joints_.size() );
153  joint_state_.velocity.resize ( joints_.size() );
154 
155  for ( int i = 0; i < joints_.size(); i++ ) {
156  physics::JointPtr joint = joints_[i];
157  double velocity = joint->GetVelocity( 0 );
158 #if GAZEBO_MAJOR_VERSION >= 8
159  double position = joint->Position ( 0 );
160 #else
161  double position = joint->GetAngle ( 0 ).Radian();
162 #endif
163  joint_state_.name[i] = joint->GetName();
164  joint_state_.position[i] = position;
165  joint_state_.velocity[i] = velocity;
166  }
168 }
gazebo::GazeboRosJointStatePublisher::update_rate_
double update_rate_
Definition: gazebo_ros_joint_state_publisher.h:80
gazebo::GazeboRosJointStatePublisher::robot_namespace_
std::string robot_namespace_
Definition: gazebo_ros_joint_state_publisher.h:76
boost::shared_ptr< ros::NodeHandle >
gazebo
gazebo::GazeboRosJointStatePublisher::OnUpdate
void OnUpdate(const common::UpdateInfo &_info)
Definition: gazebo_ros_joint_state_publisher.cpp:115
gazebo::GazeboRosJointStatePublisher::joint_names_
std::vector< std::string > joint_names_
Definition: gazebo_ros_joint_state_publisher.h:77
ROS_FATAL_NAMED
#define ROS_FATAL_NAMED(name,...)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
transform_broadcaster.h
gazebo::GazeboRosJointStatePublisher::updateConnection
event::ConnectionPtr updateConnection
Definition: gazebo_ros_joint_state_publisher.h:66
gazebo::GazeboRosJointStatePublisher::last_update_time_
common::Time last_update_time_
Definition: gazebo_ros_joint_state_publisher.h:82
gazebo::GazeboRosJointStatePublisher::publishJointStates
void publishJointStates()
Definition: gazebo_ros_joint_state_publisher.cpp:147
gazebo::GazeboRosJointStatePublisher::joint_state_publisher_
ros::Publisher joint_state_publisher_
Definition: gazebo_ros_joint_state_publisher.h:74
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
gazebo::GazeboRosJointStatePublisher::GazeboRosJointStatePublisher
GazeboRosJointStatePublisher()
Definition: gazebo_ros_joint_state_publisher.cpp:38
gazebo::GazeboRosJointStatePublisher::world_
physics::WorldPtr world_
Definition: gazebo_ros_joint_state_publisher.h:67
gazebo::GazeboRosJointStatePublisher::~GazeboRosJointStatePublisher
~GazeboRosJointStatePublisher()
Definition: gazebo_ros_joint_state_publisher.cpp:41
gazebo::GazeboRosJointStatePublisher::Load
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Definition: gazebo_ros_joint_state_publisher.cpp:45
gazebo::GazeboRosJointStatePublisher::parent_
physics::ModelPtr parent_
Definition: gazebo_ros_joint_state_publisher.h:68
gazebo::GazeboRosJointStatePublisher::update_period_
double update_period_
Definition: gazebo_ros_joint_state_publisher.h:81
transform_listener.h
gazebo::GazeboRosJointStatePublisher::tf_prefix_
std::string tf_prefix_
Definition: gazebo_ros_joint_state_publisher.h:75
ros::Time
gazebo::GazeboRosJointStatePublisher::joint_state_
sensor_msgs::JointState joint_state_
Definition: gazebo_ros_joint_state_publisher.h:73
gazebo_ros_joint_state_publisher.h
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
gazebo::GazeboRosJointStatePublisher::joints_
std::vector< physics::JointPtr > joints_
Definition: gazebo_ros_joint_state_publisher.h:69
ROS_ASSERT
#define ROS_ASSERT(cond)
gazebo::GazeboRosJointStatePublisher::rosnode_
boost::shared_ptr< ros::NodeHandle > rosnode_
Definition: gazebo_ros_joint_state_publisher.h:72
ros::NodeHandle
ros::Time::now
static Time now()


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