Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include <gazebo_plugins/gazebo_ros_joint_state_publisher.h>
00029 #include <tf/transform_broadcaster.h>
00030 #include <tf/transform_listener.h>
00031
00032 using namespace gazebo;
00033
00034 GazeboRosJointStatePublisher::GazeboRosJointStatePublisher() {}
00035
00036
00037 GazeboRosJointStatePublisher::~GazeboRosJointStatePublisher() {
00038 rosnode_->shutdown();
00039 }
00040
00041 void GazeboRosJointStatePublisher::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf ) {
00042
00043 this->parent_ = _parent;
00044 this->world_ = _parent->GetWorld();
00045
00046 this->robot_namespace_ = parent_->GetName ();
00047 if ( !_sdf->HasElement ( "robotNamespace" ) ) {
00048 ROS_INFO ( "GazeboRosJointStatePublisher Plugin missing <robotNamespace>, defaults to \"%s\"",
00049 this->robot_namespace_.c_str() );
00050 } else {
00051 this->robot_namespace_ = _sdf->GetElement ( "robotNamespace" )->Get<std::string>();
00052 if ( this->robot_namespace_.empty() ) this->robot_namespace_ = parent_->GetName ();
00053 }
00054 if ( !robot_namespace_.empty() ) this->robot_namespace_ += "/";
00055 rosnode_ = boost::shared_ptr<ros::NodeHandle> ( new ros::NodeHandle ( this->robot_namespace_ ) );
00056
00057 if ( !_sdf->HasElement ( "jointName" ) ) {
00058 ROS_ASSERT ( "GazeboRosJointStatePublisher Plugin missing jointNames" );
00059 } else {
00060 sdf::ElementPtr element = _sdf->GetElement ( "jointName" ) ;
00061 std::string joint_names = element->Get<std::string>();
00062 boost::erase_all ( joint_names, " " );
00063 boost::split ( joint_names_, joint_names, boost::is_any_of ( "," ) );
00064 }
00065
00066 this->update_rate_ = 100.0;
00067 if ( !_sdf->HasElement ( "updateRate" ) ) {
00068 ROS_WARN ( "GazeboRosJointStatePublisher Plugin (ns = %s) missing <updateRate>, defaults to %f",
00069 this->robot_namespace_.c_str(), this->update_rate_ );
00070 } else {
00071 this->update_rate_ = _sdf->GetElement ( "updateRate" )->Get<double>();
00072 }
00073
00074
00075 if ( this->update_rate_ > 0.0 ) {
00076 this->update_period_ = 1.0 / this->update_rate_;
00077 } else {
00078 this->update_period_ = 0.0;
00079 }
00080 last_update_time_ = this->world_->GetSimTime();
00081
00082 for ( unsigned int i = 0; i< joint_names_.size(); i++ ) {
00083 joints_.push_back ( this->parent_->GetJoint ( joint_names_[i] ) );
00084 ROS_INFO ( "GazeboRosJointStatePublisher is going to publish joint: %s", joint_names_[i].c_str() );
00085 }
00086
00087 ROS_INFO ( "Starting GazeboRosJointStatePublisher Plugin (ns = %s)!, parent name: %s", this->robot_namespace_.c_str(), parent_->GetName ().c_str() );
00088
00089 tf_prefix_ = tf::getPrefixParam ( *rosnode_ );
00090 joint_state_publisher_ = rosnode_->advertise<sensor_msgs::JointState> ( "joint_states",1000 );
00091
00092 last_update_time_ = this->world_->GetSimTime();
00093
00094
00095 this->updateConnection = event::Events::ConnectWorldUpdateBegin (
00096 boost::bind ( &GazeboRosJointStatePublisher::OnUpdate, this, _1 ) );
00097 }
00098
00099 void GazeboRosJointStatePublisher::OnUpdate ( const common::UpdateInfo & _info ) {
00100
00101 common::Time current_time = this->world_->GetSimTime();
00102 double seconds_since_last_update = ( current_time - last_update_time_ ).Double();
00103 if ( seconds_since_last_update > update_period_ ) {
00104
00105 publishJointStates();
00106
00107 last_update_time_+= common::Time ( update_period_ );
00108
00109 }
00110
00111 }
00112
00113 void GazeboRosJointStatePublisher::publishJointStates() {
00114 ros::Time current_time = ros::Time::now();
00115
00116 joint_state_.header.stamp = current_time;
00117 joint_state_.name.resize ( joints_.size() );
00118 joint_state_.position.resize ( joints_.size() );
00119
00120 for ( int i = 0; i < joints_.size(); i++ ) {
00121 physics::JointPtr joint = joints_[i];
00122 math::Angle angle = joint->GetAngle ( 0 );
00123 joint_state_.name[i] = joint->GetName();
00124 joint_state_.position[i] = angle.Radian () ;
00125 }
00126 joint_state_publisher_.publish ( joint_state_ );
00127 }
00128