Gazebo | Ignition | Community
Ask Your Question
1

Can you modify the state(pose/velocity/acceleration) of a model from a world plugin

asked 2014-01-31 14:58:42 -0500

vsunder gravatar image

updated 2014-02-03 13:51:55 -0500

So I want to globally control and observe the interactions of all objects in my environment. The obvious way to do this seems to be through the world plugin. However setting parameters like linear velocity seems to have no effect on the simulation. I'm curious if gazebo is internally blocking modifications of models through the world plugin or if there is a particular setting that needs to be modified to allow this to occur. Thank you

So this here's a quick simplified snippet showing as to what I'm trying to do and how:

Let me know if there is more info you would like

void World_Plugin::Load(physics::WorldPtr _parent, sdf::ElementPtr _sdf){
   this->world = _parent;
   this->updateConnection = event::Events::ConnectWorldUpdateBegin(boost::bind(&Quasistatic_World_Plugin::OnUpdate, this, _1));

 }

 //pusher vel is just some velocity
 //pusher is a modelPtr I've extracted from the world
 void World_Plugin::OnUpdate(const common::UpdateInfo & /*_info*/){
      this->pusher->SetLinearVel(math::Vector3(pusher_vel[0],pusher_vel[1], pusher_vel[2]));
 }

World File

 <?xml version="1.0"?>
 <sdf version="1.4">
  <world name="blank plane">
    <plugin name = "quasistatic_world" filename="libquasistatic_plugin.so"/>
     <include>
      <uri>model://ground_plane</uri>
     </include>
 </world>
</sdf>

The model is added in the world plugin and looks something like this (simple box for now):

<sdf version="1.4">
  <model name="pusher_box">
    <pose>0 0 0.5 0 0 0</pose>
      <static>true</static>
     <link name="link">
       <collision name="box_collision">
        <geometry>
      <box>
        <size>1 1 1</size>
      </box>
       </geometry>
      </collision>
     <visual name="visual">
      <geometry>
   <box>
    <size>1 1 1</size>
   </box>
      </geometry>
    </visual>
   </link>
   </model>
  </sdf>
edit retag flag offensive close merge delete

Comments

The syntax looks ok, assuming that this- pusher is a valid ModelPtr. Can you put a print statement in the OnUpdate function that prints this- pusher- GetWorldLinearVel() ?

scpeters gravatar imagescpeters ( 2014-02-03 13:28:19 -0500 )edit

right so when I tested this the velocity is zero. Is there some code in the background blocking me from setting the velocity of this model or there some reason the ModelPtr could be invalid. pusher is set by calling pusher = world->GetModel(0); I attempted to modify other properties like pose and the model state does not seem to update

vsunder gravatar imagevsunder ( 2014-02-03 13:34:14 -0500 )edit

Your problem is calling GetModel(0), you should pass a string with the name of your model. Using an integer will just give you the first model that was initialized, which is probably the ground_plane, which is static and always has zero velocity.

scpeters gravatar imagescpeters ( 2014-02-04 18:56:38 -0500 )edit

Alright I'll give that a shot thank you

vsunder gravatar imagevsunder ( 2014-02-06 13:50:08 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2014-01-31 18:54:31 -0500

scpeters gravatar image

World plugins are capable of affecting models. Have you started with this world plugin tutorial? That one just covers modifying gravity. I'll work on another one that manipulates several models more directly. Feel free to post your code so we can help debug it.

edit flag offensive delete link more

Comments

Ya I played with the tutorial. I guess the difference was that I didn't use the messaging system. I'll post my code show you what I tried

vsunder gravatar imagevsunder ( 2014-02-03 13:05:55 -0500 )edit

Can I see your world file?

scpeters gravatar imagescpeters ( 2014-02-03 13:39:50 -0500 )edit

Alright added that. I add models to my world from the plugin (didnt include that code cause its basically write out of the tutorial)

vsunder gravatar imagevsunder ( 2014-02-03 13:47:16 -0500 )edit

Question Tools

Stats

Asked: 2014-01-31 14:58:42 -0500

Seen: 35,532 times

Last updated: Feb 03 '14