-
Notifications
You must be signed in to change notification settings - Fork 284
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Support nested model #258
Support nested model #258
Changes from 15 commits
739f3e7
a7000fc
ca2d3cb
773eb02
a262cf2
91abd0a
4010cdf
c526eb4
88e668b
6db69f4
4519590
fcbf0dd
d48ff53
256d4db
d0ae0ec
a71a3d2
24f8db9
b9c179b
4a16b55
600575a
6b74143
3549019
6bb5bd9
8edfd1a
44cd092
fc2d91d
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,110 @@ | ||
<?xml version="1.0" ?> | ||
<sdf version="1.6"> | ||
<world name="nested_model_world"> | ||
<physics name="1ms" type="ignored"> | ||
<max_step_size>0.001</max_step_size> | ||
<real_time_factor>1.0</real_time_factor> | ||
</physics> | ||
<plugin | ||
filename="libignition-gazebo-physics-system.so" | ||
name="ignition::gazebo::systems::Physics"> | ||
<engine><filename>libignition-physics-tpe-plugin.so</filename></engine> | ||
</plugin> | ||
<plugin | ||
filename="libignition-gazebo-user-commands-system.so" | ||
name="ignition::gazebo::systems::UserCommands"> | ||
</plugin> | ||
<plugin | ||
filename="libignition-gazebo-scene-broadcaster-system.so" | ||
name="ignition::gazebo::systems::SceneBroadcaster"> | ||
</plugin> | ||
|
||
<scene> | ||
<ambient>1.0 1.0 1.0</ambient> | ||
<background>0.8 0.8 0.8</background> | ||
</scene> | ||
|
||
<light type="directional" name="sun"> | ||
<cast_shadows>true</cast_shadows> | ||
<pose>0 0 10 0 0 0</pose> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
<attenuation> | ||
<range>1000</range> | ||
<constant>0.9</constant> | ||
<linear>0.01</linear> | ||
<quadratic>0.001</quadratic> | ||
</attenuation> | ||
<direction>-0.5 0.1 -0.9</direction> | ||
</light> | ||
|
||
<model name="ground_plane"> | ||
<static>true</static> | ||
<link name="link"> | ||
<collision name="collision"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
</plane> | ||
</geometry> | ||
</collision> | ||
<visual name="visual"> | ||
<geometry> | ||
<plane> | ||
<normal>0 0 1</normal> | ||
<size>100 100</size> | ||
</plane> | ||
</geometry> | ||
<material> | ||
<ambient>0.8 0.8 0.8 1</ambient> | ||
<diffuse>0.8 0.8 0.8 1</diffuse> | ||
<specular>0.8 0.8 0.8 1</specular> | ||
</material> | ||
</visual> | ||
</link> | ||
</model> | ||
|
||
<model name="model_00"> | ||
<pose>0 0 0.5 0 0 0</pose> | ||
<link name="link_00"> | ||
<pose>0 0 0 0 0 0</pose> | ||
<collision name="collision_00"> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
</collision> | ||
<visual name="visual_00"> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
</visual> | ||
</link> | ||
|
||
<model name="model_01"> | ||
<pose>1 0 0.0 0 0 0</pose> | ||
<link name="link_01"> | ||
<pose>0.25 0 0.0 0 0 0.785398</pose> | ||
<collision name="collision_01"> | ||
<geometry> | ||
<box> | ||
<size>1 1 1</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
<visual name="visual_01"> | ||
<geometry> | ||
<box> | ||
<size>1 1 1</size> | ||
</box> | ||
</geometry> | ||
</visual> | ||
</link> | ||
</model> | ||
</model> | ||
|
||
</world> | ||
</sdf> |
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -155,6 +155,18 @@ namespace ignition | |
/// \param[in] _parent Entity which should be _child's parent. | ||
public: void SetParent(Entity _child, Entity _parent); | ||
|
||
/// \brief Overloaded function to recursively create model entities | ||
/// and make sure a) only one canonical link is created per model tree, | ||
/// and b) we override the nested model's static property to true if | ||
/// its parent is static | ||
/// \param[in] _model SDF model object. | ||
/// \param[in] _createCanonicalLink True to create a canonical link | ||
/// component and attach to its child link entity | ||
/// \param[in] _staticParent True if parent is static, false otherwise. | ||
/// \return Model entity. | ||
private: Entity CreateEntities(const sdf::Model *_model, | ||
azeey marked this conversation as resolved.
Show resolved
Hide resolved
|
||
bool _createCanonicalLink, bool _staticParent); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Is static the only option that the nested models will ever override? Maybe consider passing some type that can be extended in the future. A map with key-value pairs? Or maybe it's not worth it... There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm not sure what other params will be added. This function has evolved as I get more info about the proposed nested model spec. I'm leaning towards leaving as is for now since it's private and we can change it later if we need too. |
||
|
||
/// \brief Pointer to private data. | ||
private: std::unique_ptr<SdfEntityCreatorPrivate> dataPtr; | ||
}; | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
nit:
1.6
->1.7
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
done. 6b74143