Changing Model Texture during runtime with python but material script can't be renamed
Hey,
I am trying to dynamically change the texture of a box. The model structure of the first model currently looks like this:
My material script:
material RedShape
{
technique
{
pass
{
texture_unit
{
texture wall.png
scale 1 1
}
}
}
and my model.sdf:
<?xml version='1.0'?>
<sdf version='1.7'>
<model name='wall_001'>
<static>0</static>
<link name='link_001'>
<collision name="wall_001_collision">
<geometry>
<box>
<size>1 3 2.5</size>
</box>
</geometry>
</collision>
<visual name='wall_001_visual'>
<cast_shadows>true</cast_shadows>
<geometry>
<box>
<size>1 5 2.5</size>
</box>
</geometry>
<material>
<script>
<uri>model://wall_001/materials/scripts/</uri>
<uri>model://wall_001/materials/textures/</uri>
<name>RedShape</name>
</script>
<material>
</visual>
</link>
</model>
</sdf>
Python code spawning the models:
def spawn_wall(wall_name, orientation):
path = r"irb4600_40_255_moveit_config/worlds/models/{}/model.sdf".format(wall_name)
wall_xml = get_model_xml(path)
print("Spawning model: {}".format(wall_name))
rospy.wait_for_service("gazebo/spawn_sdf_model")
spawn_model = rospy.ServiceProxy("gazebo/spawn_sdf_model", SpawnModel)
wall_pose = Pose(Point(x=2.2, y=0, z=1.25), orientation)
spawn_model(wall_name, wall_xml, "", wall_pose, "world")
The problem I have: I can't change the model during runtime either by respawning the model with another .png texture or by respawning a completely different model with the same material script. (I have the feeling it is due to the material script having the same name, but I can't change it as weirdly only RedShape works for me right now.) The first model I spawn gets spawned afterward as well, although I change the texture file.
When changing the material name from RedShape, which so far works well, to another name like WallShape, no texture at all gets spawned, instead, all is grey. My feeling is I need to figure out how to get another material to work, and when spawning different walls, the different textures should get displayed. How do I do that?
I would highly appreciate your answers, thanks a lot for reading so far
Cheers