28 #include <boost/algorithm/string.hpp> 45 this->
world_ = _parent->GetWorld();
48 if ( !_sdf->HasElement (
"robotNamespace" ) ) {
49 ROS_INFO_NAMED(
"joint_state_publisher",
"GazeboRosJointStatePublisher Plugin missing <robotNamespace>, defaults to \"%s\"",
52 this->
robot_namespace_ = _sdf->GetElement (
"robotNamespace" )->Get<std::string>();
58 if ( !_sdf->HasElement (
"jointName" ) ) {
59 ROS_ASSERT (
"GazeboRosJointStatePublisher Plugin missing jointNames" );
61 sdf::ElementPtr element = _sdf->GetElement (
"jointName" ) ;
62 std::string joint_names = element->Get<std::string>();
63 boost::erase_all ( joint_names,
" " );
64 boost::split (
joint_names_, joint_names, boost::is_any_of (
"," ) );
68 if ( !_sdf->HasElement (
"updateRate" ) ) {
69 ROS_WARN_NAMED(
"joint_state_publisher",
"GazeboRosJointStatePublisher Plugin (ns = %s) missing <updateRate>, defaults to %f",
72 this->
update_rate_ = _sdf->GetElement (
"updateRate" )->Get<
double>();
81 #if GAZEBO_MAJOR_VERSION >= 8 87 for (
unsigned int i = 0; i<
joint_names_.size(); i++ ) {
93 ROS_INFO_NAMED(
"joint_state_publisher",
"GazeboRosJointStatePublisher is going to publish joint: %s",
joint_names_[i].c_str() );
101 #if GAZEBO_MAJOR_VERSION >= 8 104 last_update_time_ = this->
world_->GetSimTime();
114 #if GAZEBO_MAJOR_VERSION >= 8 115 common::Time current_time = this->
world_->SimTime();
117 common::Time current_time = this->
world_->GetSimTime();
121 ROS_WARN_NAMED(
"joint_state_publisher",
"Negative joint state update time difference detected.");
125 double seconds_since_last_update = ( current_time -
last_update_time_ ).Double();
145 for (
int i = 0; i <
joints_.size(); i++ ) {
146 physics::JointPtr joint =
joints_[i];
147 double velocity = joint->GetVelocity( 0 );
148 #if GAZEBO_MAJOR_VERSION >= 8 149 double position = joint->Position ( 0 );
151 double position = joint->GetAngle ( 0 ).Radian();
event::ConnectionPtr updateConnection
#define ROS_INFO_NAMED(name,...)
GazeboRosJointStatePublisher()
std::string getPrefixParam(ros::NodeHandle &nh)
#define ROS_WARN_NAMED(name,...)
physics::ModelPtr parent_
~GazeboRosJointStatePublisher()
std::vector< physics::JointPtr > joints_
std::string robot_namespace_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
boost::shared_ptr< ros::NodeHandle > rosnode_
void publish(const boost::shared_ptr< M > &message) const
void publishJointStates()
sensor_msgs::JointState joint_state_
common::Time last_update_time_
ros::Publisher joint_state_publisher_
std::vector< std::string > joint_names_
void OnUpdate(const common::UpdateInfo &_info)
#define ROS_FATAL_NAMED(name,...)