Gazebo | Ignition | Community
Ask Your Question
0

Delete a model from within its own modelPlugin

asked 2020-07-10 13:03:52 -0500

rezenders gravatar image

I wrote a ModelPlugin to delete the model to which it is attached after a certain period of time. The problem is that when the model is deleted, gazebo stops working, it just freezes.

Plugin code:

#include <ignition/math/Pose3.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/physics/Model.hh>
#include "gazebo_msgs/DeleteModel.h"
#include "ros/ros.h"
#include <thread>
#include <chrono>


namespace gazebo{
  class VictimPlugin : public ModelPlugin{
  private:
    physics::ModelPtr model;

    int drowning_time_ = 0;
    std::thread timer_thread_;

    void timerThreadFunction(){
      std::this_thread::sleep_for(
        std::chrono::milliseconds(this->drowning_time_));

      gazebo_msgs::DeleteModel del_model;
      del_model.request.model_name = this->model->GetName();
      ros::service::call("/gazebo/delete_model", del_model);

   }

  public:
    VictimPlugin() : ModelPlugin(){}
    ~VictimPlugin(){
      timer_thread_.join();
    }

    void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf){
      model = _model;

      if (!_sdf->HasElement("drowningTime")){
        this->drowning_time_ = 5000;
        ROS_DEBUG("Victim plugin missing <drowningTime>, default to 5000ms");
      }else{
        this->drowning_time_ = _sdf->Get<int>("drowningTime");
      }

      this->timer_thread_ =
        std::thread(std::bind(&VictimPlugin::timerThreadFunction, this));
    }
  };
  GZ_REGISTER_MODEL_PLUGIN(VictimPlugin)
}

I am adding the model to the world file like this:

<include>
  <name>victim_randy</name>
  <pose>7 17.5 0.1 -1.57 0 0</pose>
  <uri>model://rescue_randy</uri>
  <plugin name="victim" filename="libvictim.so">
    <drowningTime>5000</drowningTime>
  </plugin>
</include>

I am using gazebo version 9.13.1

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-07-10 14:50:09 -0500

updated 2020-07-10 14:51:11 -0500

The problem is that you do not allow the destructor to return. Your thread never joins due to the service call.

You can use directly the gazebo interface to delete the model, which will allow you to do this asynchronously.

#include <gazebo/transport/Node.hh>
transport::NodePtr node = boost::make_shared<transport::Node>();
node->Init();
transport::PublisherPtr request_pub = node->Advertise<msgs::Request>("~/request");
msgs::Request *msg = msgs::CreateRequest("entity_delete", model->GetName());
request_pub->Publish(*msg);
delete msg;
edit flag offensive delete link more

Comments

That makes sense, it worked. Thank you!

rezenders gravatar imagerezenders ( 2020-07-13 09:01:22 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-07-10 13:03:52 -0500

Seen: 1,974 times

Last updated: Jul 10 '20