Skip to content

Commit

Permalink
Remove node_name from <ros> SDF tag (#804)
Browse files Browse the repository at this point in the history
* Rename Node::Create to Node::Get

* Node::Get without node name

* Remove node_name support from SDF

* wip get name from plugin name

* Remove node name argument (will be inferred from sdf)

* fix tests and implement static shared node

* Adding test file
  • Loading branch information
dhood authored and chapulina committed Aug 28, 2018
1 parent 63a3718 commit 46d4e34
Show file tree
Hide file tree
Showing 26 changed files with 131 additions and 87 deletions.
3 changes: 0 additions & 3 deletions gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,6 @@ class GazeboRosForcePrivate;
<ros>
<!-- Override default node name -->
<node_name>force_test_node</node_name>
<!-- Add a namespace -->
<namespace>/test</namespace>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,9 +52,6 @@ class GazeboRosJointStatePublisherPrivate;
<ros>
<!-- Override default node name -->
<node_name>my_joint_state_publisher</node_name>
<!-- Add a namespace -->
<namespace>/ny_namespace</namespace>
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_force.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ void GazeboRosForce::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf)
}

// Subscribe to wrench messages
impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ros_force", sdf);
impl_->ros_node_ = gazebo_ros::Node::Get(sdf);

impl_->wrench_sub_ = impl_->ros_node_->create_subscription<geometry_msgs::msg::Wrench>(
"gazebo_ros_force", std::bind(&GazeboRosForce::OnRosWrenchMsg, this,
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_imu_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ GazeboRosImuSensor::~GazeboRosImuSensor()

void GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{
impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ros_imu_sensor", _sdf);
impl_->ros_node_ = gazebo_ros::Node::Get(_sdf);

impl_->sensor_ = std::dynamic_pointer_cast<gazebo::sensors::ImuSensor>(_sensor);
if (!impl_->sensor_) {
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ GazeboRosJointStatePublisher::~GazeboRosJointStatePublisher()
void GazeboRosJointStatePublisher::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf)
{
// ROS node
impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ros_joint_state_publisher", sdf);
impl_->ros_node_ = gazebo_ros::Node::Get(sdf);

// Joints
if (!sdf->HasElement("joint_name")) {
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_ray_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ GazeboRosRaySensor::~GazeboRosRaySensor()
void GazeboRosRaySensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{
// Create ros_node configured from sdf
impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ray_sensor", _sdf);
impl_->ros_node_ = gazebo_ros::Node::Get(_sdf);

// Get tf frame for output
impl_->frame_name_ = gazebo_ros::SensorFrameID(*_sensor, *_sdf);
Expand Down
2 changes: 1 addition & 1 deletion gazebo_plugins/src/gazebo_ros_template.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ void GazeboRosTemplate::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sd
// Create a GazeboRos node instead of a common ROS node.
// Pass it SDF parameters so common options like namespace and remapping
// can be handled.
impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ros_template", sdf);
impl_->ros_node_ = gazebo_ros::Node::Get(sdf);

// The model pointer gives you direct access to the physics object,
// for example:
Expand Down
1 change: 0 additions & 1 deletion gazebo_plugins/test/worlds/gazebo_ros_force.world
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
</link>
<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">
<ros>
<node_name>force_test_node</node_name>
<namespace>/test</namespace>
<argument>gazebo_ros_force:=force_test</argument>
</ros>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,6 @@
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<node_name>joint_state_publisher_test_node</node_name>
<namespace>/test</namespace>
<argument>joint_states:=joint_states_test</argument>
</ros>
Expand Down
8 changes: 0 additions & 8 deletions gazebo_plugins/test/worlds/gazebo_ros_ray_sensor.world
Original file line number Diff line number Diff line change
Expand Up @@ -49,31 +49,27 @@
<!-- Instance of ray plugin for each output type -->
<plugin name="pc2" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc2</node_name>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc</node_name>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="ls" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>ls</node_name>
<namespace>/ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>range</node_name>
<namespace>/ray</namespace>
<argument>~/out:=range</argument>
</ros>
Expand All @@ -83,31 +79,27 @@
<!-- Disabled while gpu laser is broken in gazebo9, see https://bitbucket.org/osrf/gazebo/issues/2486/conflicts-between-vertical-gpu-rays-and
<plugin name="pc2_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc2</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="ls_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>ls</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>range</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=range</argument>
</ros>
Expand Down
1 change: 0 additions & 1 deletion gazebo_plugins/worlds/gazebo_ros_force_demo.world
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@
</link>
<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">
<ros>
<node_name>force_demo_node</node_name>
<namespace>/demo</namespace>
<argument>gazebo_ros_force:=force_demo</argument>
</ros>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<node_name>joint_state_publisher_demo_node</node_name>
<namespace>/demo</namespace>
<argument>joint_states:=joint_states_demo</argument>
</ros>
Expand Down
16 changes: 4 additions & 12 deletions gazebo_plugins/worlds/gazebo_ros_ray_sensor_demo.world
Original file line number Diff line number Diff line change
Expand Up @@ -81,31 +81,27 @@
<update_rate>1.0</update_rate>
<plugin name="pc2" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc2</node_name>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc</node_name>
<namespace>/ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>laserscan</node_name>
<namespace>/ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>range</node_name>
<namespace>/ray</namespace>
<argument>~/out:=range</argument>
</ros>
Expand Down Expand Up @@ -140,33 +136,29 @@
</ray>
<always_on>true</always_on>
<update_rate>1.0</update_rate>
<plugin name="pc2" filename="libgazebo_ros_ray_sensor.so">
<plugin name="pc2_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc2</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud2</argument>
</ros>
<output_type>sensor_msgs/PointCloud2</output_type>
</plugin>
<plugin name="pc" filename="libgazebo_ros_ray_sensor.so">
<plugin name="pc_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>pc</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=pointcloud</argument>
</ros>
<output_type>sensor_msgs/PointCloud</output_type>
</plugin>
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<plugin name="laserscan_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>laserscan</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=laserscan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
</plugin>
<plugin name="range" filename="libgazebo_ros_ray_sensor.so">
<plugin name="range_gpu" filename="libgazebo_ros_ray_sensor.so">
<ros>
<node_name>range</node_name>
<namespace>/gpu_ray</namespace>
<argument>~/out:=range</argument>
</ros>
Expand Down
1 change: 0 additions & 1 deletion gazebo_plugins/worlds/gazebo_ros_template_demo.world
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
<static>true</static>
<plugin name="gazebo_ros_template" filename="libgazebo_ros_template.so">
<ros>
<node_name>demo_node</node_name>
<namespace>/demo</namespace>
</ros>
</plugin>
Expand Down
47 changes: 26 additions & 21 deletions gazebo_ros/include/gazebo_ros/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,39 +42,41 @@ class Node : public rclcpp::Node
/// Destructor
virtual ~Node();

/// Create a #gazebo_ros::Node and add it to the global #gazebo_ros::Executor.
/// Get a static node called "gazebo" which can be shared by several plugins.
/**
* \details This will call rclcpp::init if it hasn't been called yet.
* \param[in] node_name Name for the new node to create
* \return A shared pointer to a new #gazebo_ros::Node
* \details The node is created the first time this is called.
* \return A shared pointer to a #gazebo_ros::Node
*/
static SharedPtr Create(const std::string & node_name);
static SharedPtr Get();

/// Create a #gazebo_ros::Node and add it to the global #gazebo_ros::Executor.
/// Get reference to a #gazebo_ros::Node and add it to the global #gazebo_ros::Executor.
/**
* \details This will create a new node; the node's name will be the same as the name argument
* on the <plugin> tag.
* \details This will call rclcpp::init if it hasn't been called yet.
* \details Sets namespace, remappings, and parameters from SDF.
* \details Sets node name, namespace, remappings, and parameters from SDF.
* SDF is in the form:
* \code{.xml}
* <!-- Optional configurations for a plugin's Node -->
* <ros>
* <!-- Name of node, only use if plugin is one node -->
* <node_name>my_node</node_name>
* <!-- Namespace of the node -->
* <namespace>/my_ns</namespace>
* <!-- Command line arguments sent to Node's constructor for remappings -->
* <argument>my_topic:=new_topic</argument>
* <argument>__name:=super_cool_node</argument>
* <!-- Initial ROS params set for node -->
* <parameter name="max_velocity" type="int">55</parameter>
* <parameter name="publish_odom" type="bool">True</parameter>
* </ros>
* <!-- Node name will be the same as the plugin name -->
* <plugin name="my_node_name" filename="my_library.so">
* <!-- Optional configurations for a plugin's Node -->
* <ros>
* <!-- Namespace of the node -->
* <namespace>/my_ns</namespace>
* <!-- Command line arguments sent to Node's constructor for remappings -->
* <argument>my_topic:=new_topic</argument>
* <argument>__name:=super_cool_node</argument>
* <!-- Initial ROS params set for node -->
* <parameter name="max_velocity" type="int">55</parameter>
* <parameter name="publish_odom" type="bool">True</parameter>
* </ros>
* </plugin>
* \endcode
* \param[in] node_name Name of node to create
* \param[in] _sdf An SDF element in the style above or containing a <ros> tag in the style above
* \return A shared pointer to a new #gazebo_ros::Node
*/
static SharedPtr Create(const std::string & node_name, sdf::ElementPtr _sdf);
static SharedPtr Get(sdf::ElementPtr _sdf);

/// Create a #gazebo_ros::Node and add it to the global #gazebo_ros::Executor.
/**
Expand Down Expand Up @@ -118,6 +120,9 @@ class Node : public rclcpp::Node
/// Points to an #gazebo_ros::Executor shared between all #gazebo_ros::Node instances
static std::weak_ptr<Executor> static_executor_;

/// Points to a #gazebo_ros::Node which can be shared among several plugins.
static std::weak_ptr<Node> static_node_;

/// Gets a logger to log information internal to the node
static rclcpp::Logger internal_logger();
};
Expand Down
2 changes: 1 addition & 1 deletion gazebo_ros/src/gazebo_ros_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void GazeboRosInit::Load(int argc, char ** argv)
// Initialize ROS with arguments
rclcpp::init(argc, argv);

impl_->ros_node_ = gazebo_ros::Node::Create("gazebo_ros_clock");
impl_->ros_node_ = gazebo_ros::Node::Get();

// Offer transient local durability on the clock topic so that if publishing is infrequent (e.g.
// the simulation is paused), late subscribers can receive the previously published message(s).
Expand Down
33 changes: 21 additions & 12 deletions gazebo_ros/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,28 +23,30 @@ namespace gazebo_ros
{

std::weak_ptr<Executor> Node::static_executor_;
std::weak_ptr<Node> Node::static_node_;
std::mutex Node::lock_;

Node::~Node()
{
}

Node::SharedPtr Node::Create(const std::string & node_name, sdf::ElementPtr sdf)
Node::SharedPtr Node::Get(sdf::ElementPtr sdf)
{
// Get inner <ros> element if full plugin sdf was passed in
if (sdf->HasElement("ros")) {
sdf = sdf->GetElement("ros");
}

// Initialize arguments
std::string name = node_name;
std::string name = "";
std::string ns = "";
std::vector<std::string> arguments;
std::vector<rclcpp::Parameter> initial_parameters;

// Override name if tag is present
if (sdf->HasElement("node_name")) {
name = sdf->GetElement("node_name")->Get<std::string>();
// Get the name of the plugin as the name for the node.
if (!sdf->HasAttribute("name")) {
RCLCPP_WARN(internal_logger(), "Name of plugin not found.");
}
name = sdf->Get<std::string>("name");

// Get inner <ros> element if full plugin sdf was passed in
if (sdf->HasElement("ros")) {
sdf = sdf->GetElement("ros");
}

// Set namespace if tag is present
Expand Down Expand Up @@ -85,9 +87,16 @@ Node::SharedPtr Node::Create(const std::string & node_name, sdf::ElementPtr sdf)
arguments, initial_parameters);
}

Node::SharedPtr Node::Create(const std::string & node_name)
Node::SharedPtr Node::Get()
{
return CreateWithArgs(node_name);
Node::SharedPtr node = static_node_.lock();

if (!node) {
node = CreateWithArgs("gazebo");
static_node_ = node;
}

return node;
}

rclcpp::Parameter Node::sdf_to_ros_parameter(sdf::ElementPtr const & sdf)
Expand Down
Loading

0 comments on commit 46d4e34

Please sign in to comment.