Skip to content

Commit

Permalink
Remove node name argument (will be inferred from sdf)
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Aug 24, 2018
1 parent 1df6036 commit a85e876
Show file tree
Hide file tree
Showing 9 changed files with 18 additions and 17 deletions.
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::Get("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 @@ -57,7 +57,7 @@ GazeboRosImuSensor::~GazeboRosImuSensor()

void GazeboRosImuSensor::Load(gazebo::sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
{
impl_->ros_node_ = gazebo_ros::Node::Get("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::Get("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::Get("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::Get("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
2 changes: 1 addition & 1 deletion gazebo_plugins/test/worlds/gazebo_ros_imu_sensor.world
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@
</z>
</linear_acceleration>
</imu>
<plugin name="my_imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<plugin name="my_imuasdf_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<namespace>/imu</namespace>
<argument>~/out:=data</argument>
Expand Down
3 changes: 1 addition & 2 deletions gazebo_ros/include/gazebo_ros/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,11 +67,10 @@ class Node : public rclcpp::Node
* <parameter name="publish_odom" type="bool">True</parameter>
* </ros>
* \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 Get(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
18 changes: 10 additions & 8 deletions gazebo_ros/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,22 +29,24 @@ Node::~Node()
{
}

Node::SharedPtr Node::Get(const std::string & node_name, sdf::ElementPtr sdf)
Node::SharedPtr Node::Get(sdf::ElementPtr sdf)
{
// Initialize arguments
std::string name = "";
if (!name = sdf->Attribute("name")) {
ignerr << "Name not passed" << std::endl;
std::string ns = "";
std::vector<std::string> arguments;
std::vector<rclcpp::Parameter> initial_parameters;

// 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");
}

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

// Set namespace if tag is present
if (sdf->HasElement("namespace")) {
ns = sdf->GetElement("namespace")->Get<std::string>();
Expand Down
2 changes: 1 addition & 1 deletion gazebo_ros/test/plugins/sdf_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class SDFNode : public gazebo::WorldPlugin
void SDFNode::Load(gazebo::physics::WorldPtr, sdf::ElementPtr _sdf)
{
// It should be ok to create a node without calling init first.
auto node = gazebo_ros::Node::Get("sdf_node", _sdf);
auto node = gazebo_ros::Node::Get(_sdf);
assert(nullptr != node);

const char * node_name = node->get_name();
Expand Down

0 comments on commit a85e876

Please sign in to comment.