Skip to content

Commit

Permalink
Added ifdef to publish the data with bigger version than Gazebo 9.14 …
Browse files Browse the repository at this point in the history
…and Gazebo 11.1

Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Aug 28, 2020
1 parent ee5430e commit 6787a96
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
3 changes: 2 additions & 1 deletion gazebo_ros/include/gazebo_ros/gazebo_ros_api_plugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -292,9 +292,10 @@ class GazeboRosApiPlugin : public SystemPlugin
/// \brief Unused
void onResponse(ConstResponsePtr &response);

#if (GAZEBO_MAJOR_VERSION == 11 && GAZEBO_MINOR_VERSION > 1) || (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 14)
/// \brief Subscriber callback for performance metrics. This will be send in the ROS network
void onPerformanceMetrics(const boost::shared_ptr<gazebo::msgs::PerformanceMetrics const> &msg);

#endif
/// \brief utility for checking if string is in URDF format
bool isURDF(std::string model_xml);

Expand Down
8 changes: 6 additions & 2 deletions gazebo_ros/src/gazebo_ros_api_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,9 +193,10 @@ void GazeboRosApiPlugin::loadGazeboRosApiPlugin(std::string world_name)
light_modify_pub_ = gazebonode_->Advertise<gazebo::msgs::Light>("~/light/modify");
request_pub_ = gazebonode_->Advertise<gazebo::msgs::Request>("~/request");
response_sub_ = gazebonode_->Subscribe("~/response",&GazeboRosApiPlugin::onResponse, this);
#if (GAZEBO_MAJOR_VERSION == 11 && GAZEBO_MINOR_VERSION > 1) || (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 14)
performance_metric_sub_ = gazebonode_->Subscribe("/gazebo/performance_metrics",
&GazeboRosApiPlugin::onPerformanceMetrics, this);

#endif
// reset topic connection counts
pub_link_states_connection_count_ = 0;
pub_model_states_connection_count_ = 0;
Expand Down Expand Up @@ -227,7 +228,7 @@ void GazeboRosApiPlugin::onResponse(ConstResponsePtr &response)
{

}

#if (GAZEBO_MAJOR_VERSION == 11 && GAZEBO_MINOR_VERSION > 1) || (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 14)
void GazeboRosApiPlugin::onPerformanceMetrics(const boost::shared_ptr<gazebo::msgs::PerformanceMetrics const> &msg)
{
gazebo_msgs::PerformanceMetrics msg_ros;
Expand All @@ -253,6 +254,7 @@ void GazeboRosApiPlugin::onPerformanceMetrics(const boost::shared_ptr<gazebo::ms

pub_performance_metrics_.publish(msg_ros);
}
#endif

void GazeboRosApiPlugin::gazeboQueueThread()
{
Expand Down Expand Up @@ -409,8 +411,10 @@ void GazeboRosApiPlugin::advertiseServices()
ros::VoidPtr(), &gazebo_queue_);
pub_model_states_ = nh_->advertise(pub_model_states_ao);

#if (GAZEBO_MAJOR_VERSION == 11 && GAZEBO_MINOR_VERSION > 1) || (GAZEBO_MAJOR_VERSION == 9 && GAZEBO_MINOR_VERSION > 14)
// publish performance metrics
pub_performance_metrics_ = nh_->advertise<gazebo_msgs::PerformanceMetrics>("performance_metrics", 10);
#endif

// Advertise more services on the custom queue
std::string set_link_properties_service_name("set_link_properties");
Expand Down

0 comments on commit 6787a96

Please sign in to comment.