Gazebo | Ignition | Community
Ask Your Question
0

Unable to InsertModelSDF into World from model plugin (Bug or Error??)

asked 2018-11-13 09:10:45 -0500

wentz gravatar image

updated 2018-11-19 07:52:04 -0500

I'm working on a ModelPlugin that spawns a new model and adjusts the position of the model based on the other model's position. To do this i create an sdf::SDF from string and spawn it with the function world->InsertModelSDF(modelSDF). The function looks like this:

std::string sensor_pose_as = pose3dToString(this->link_pose);
    sdf::SDF modelSDF;
    modelSDF.SetFromString(
    "<sdf version='1.6'>\
    <model name='Particle_"+this->parent_save_name_+"'>\
    <link name='link_"+this->particle_link_name_+"'>\
      <pose frame=''>"+sensor_pose_as+"</pose>\
      <gravity>0</gravity>\
      <self_collide>0</self_collide>\
      <kinematic>0</kinematic>\
      <visual name='visual_0'>\
        <pose>"+std::to_string(this->p_range)+" 0 0 0 -0 0</pose>\
        <geometry>\
          <box>\
            <size>"+std::to_string(p_size)+" "+std::to_string(p_size)+" 0.001</size>\
          </box>\
        </geometry>\
        <material>\
          <lighting>0</lighting>\
          <script>\
            <uri>file://media/materials/scripts/gazebo.material</uri>\
            <name>Gazebo/Grey</name>\
          </script>\
        </material>\
        <transparency>"+std::to_string(this->p_transparency_)+"</transparency>\
        <cast_shadows>0</cast_shadows>\
      </visual>\
    </link>\
    <static>0</static>\
    </model>\
    </sdf>");
    sdf::ElementPtr model = modelSDF.Root()->GetElement("model");

    for(int i=1; i<=this->num_particles; i++)
    {
            //do other stuff
    }

    ROS_INFO("Insert Model into World");
    this->model_ = model;
    this->world_->InsertModelSDF(modelSDF);
    //this->parent_->GetWorld()->InsertModelString(modelSDF.ToString());

    common::Time::MSleep(1000);
    ROS_INFO("Setting Pose");
    math::Pose p = math::Pose(this->link_pose);
    this->particle_model_ = this->parent_->GetWorld()->GetModel("Particle_"+this->parent_save_name_);

    ROS_INFO("2 %s",this->particle_model_->GetName().c_str());
    this->particle_model_->SetLinkWorldPose(p, this->particle_link_name_);
    ROS_INFO("Particle Model loaded properly");

I used the exact same function in a SensorPlugin and it worked perfectly. When i debugged the programm this

this->particle_model_ = this->parent_->GetWorld()->GetModel("Particle_"+this->parent_save_name_);

always return NULL. Already checked the modelSDF Variable in a extern file and it's okay. Don't know if its a bug since it worked perfectly in my other Plugin.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2018-11-19 12:29:29 -0500

chapulina gravatar image

Sensor plugins run in a separate thread, so when you sleep your plugin for a second, the physics thread is taking care of inserting the model. Model plugins on the other hand run in the physics thread, so when you sleep, you're halting even the code which should be processing the model insertion.

There are several ways to work around this, you could publish a factory message from a different thread and block only that thread until the model is inserted, you can get the model on a later callback, or maybe pause the world, step it a few times and then unpause it... Just some ideas ;)

edit flag offensive delete link more

Comments

Thanks, guess this will fix my problem and i learned something new :). Unfortunately i will not be able to check it until next week probably. Anyway thanks a lot and have a nice week.

wentz gravatar imagewentz ( 2018-11-20 06:05:05 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-11-13 09:10:45 -0500

Seen: 285 times

Last updated: Nov 19 '18