How to write the gazebo plugin so that the publish topic includes namespace

asked 2021-04-02 19:09:02 -0500

Kolohe113 gravatar image

updated 2021-04-02 19:09:13 -0500

   <group ns="robot0">
        <include file="$(find px4)/launch/single_vehicle_spawn_sdf.launch">
            <arg name="x" value="0"/>
        </include>
    </group>

I have a sonar plugin located in a sdf which is called by single_vehicle_spawn_sdf.launch. I notice that it is not publishing the topic with group ns; right now it is publishing /sonar instead of /robot0/sonar.

Here are the plugin files, header file:

#include <gazebo/common/Plugin.hh>
#include <gazebo/gazebo.hh>
#include <sensor_msgs/Range.h>
#include <ros/ros.h>

namespace gazebo {
class RosSonarPlugin: public SensorPlugin{
public:
    RosSonarPlugin(){topicName = "sonar";}
    virtual ~RosSonarPlugin(){}

    virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
    virtual void onUpdated();

protected:
    //sensors::ImuSensorPtr imu_;
    sensors::SonarSensorPtr sonar_;

    event::ConnectionPtr updated_conn_;

    //sensor_msgs::Imu imu_msg_;
    sensor_msgs::Range sonar_msg_;

    ros::NodeHandle* node_handle_;
    ros::Publisher pub_;
    std::string topicName;
};
}

cpp file:

#include "header_sonar.h"
#include "gazebo/sensors/SonarSensor.hh"

namespace gazebo{
void RosSonarPlugin::Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf){
    // Make sure the ROS node for Gazebo has already been initialized
    if (!ros::isInitialized())
    {
      ROS_INFO("ROS should be initialized first!");
      return;
    }

    if (!_sensor)
        gzerr << "Invalid sensor pointer.\n";

    this->sonar_ = std::dynamic_pointer_cast<sensors::SonarSensor>(_sensor);
    //if (!this->imu_){
    if (!this->sonar_){
        gzerr << "SonarPlugin equires a SonarSensor.\n";
        return;
    }

    ROS_INFO("The Sonar plugin has been loaded!");

    node_handle_ = new ros::NodeHandle("");
    pub_ = node_handle_->advertise<sensor_msgs::Range>(topicName, 1);

    this->updated_conn_ = this->sonar_->ConnectUpdated(
                boost::bind(&RosSonarPlugin::onUpdated,this));
}

void RosSonarPlugin::onUpdated(){
    //copy data into ros message

    sonar_msg_.header.frame_id = "drone_link";
    sonar_msg_.header.stamp.sec = this->sonar_->LastUpdateTime().sec;
    sonar_msg_.header.stamp.nsec = this->sonar_->LastUpdateTime().nsec;

    sonar_msg_.range = this->sonar_->Range();
    sonar_msg_.max_range = this->sonar_->RangeMax();
    sonar_msg_.min_range = this->sonar_->RangeMin();

    pub_.publish(sonar_msg_);
}

GZ_REGISTER_SENSOR_PLUGIN(sonarPlugin)

I want the topic to be /robot0/sonar. Any help will be appeciated, thank you. }

edit retag flag offensive close merge delete

Comments

Hi, have you solved the problem? I'm having the same issue.

Kevin1719 gravatar image Kevin1719  ( 2021-12-17 01:51:57 -0500 )edit