Migration from Gazebo-classic: Model API
When migrating plugins from Gazebo-classic to Ignition Gazebo, developers will notice that the C++ APIs for both simulators are quite different. Be sure to check the plugin migration tutorial to get a high-level view of the architecture differences before using this guide.
This tutorial is meant to serve as a reference guide for developers migrating functions from the sim::physics::Model class.
If you're trying to use some API which doesn't have an equivalent on Ignition yet, feel free to ticket an issue.
Model API
Gazebo-classic's sim::physics::Model
provides lots of functionality, which can be divided in these categories:
- Properties: Setting / getting properties
- Example: Model::GetName / Model::SetName
- Read family: Getting children and parent
- Example: Model::GetLink
- Write family: Adding children, changing parent
- Example: Model::RemoveChildren
- Lifecycle: Functions to control the model's lifecycle
- Example: Model::Init
- Others: Functions that don't fit any of the categories above
- Example: Model::PlaceOnEntity
You'll find the Ignition APIs below on the following headers:
- ignition/gazebo/Model.hh
- ignition/gazebo/Util.hh
- ignition/gazebo/SdfEntityCreator.hh
- ignition/gazebo/EntityComponentManager.hh
It's worth remembering that most of this functionality can be performed using the EntityComponentManager directly. The functions presented here exist for convenience and readability.
Properties
Most of Gazebo-classic's Model API is related to setting and getting properties. These functions are great candidates to have equivalents on Ignition Gazebo, because the Entity-Component-System architecture is perfect for setting components (properties) into entities such as models.
Classic | Ignition |
---|---|
AddType | ecm.CreateComponent<Type>(entity, Type()) |
BoundingBox | TODO |
CollisionBoundingBox | TODO |
DirtyPose | Not supported |
FillMsg | TODO |
GetAutoDisable | TODO |
GetId | gz::sim::Model::Entity |
GetName | gz::sim::Model::Name |
GetPluginCount | TODO |
GetSDF | TODO |
GetSDFDom | TODO |
GetSaveable | Not supported |
GetScopedName | gz::sim::scopedName |
GetSelfCollide | gz::sim::Model::SelfCollide |
GetType | gz::sim::entityType |
GetWorldEnergy | TODO |
GetWorldEnergyKinetic | TODO |
GetWorldEnergyPotential | TODO |
HasType | sim::components::Model::typeId == entityTypeId(entity, ecm) |
InitialRelativePose | TODO |
IsCanonicalLink | See link API |
IsSelected | Selection is client-specific, not porting |
IsStatic | gz::sim::Model::Static |
PluginInfo | TODO |
TODO | |
ProcessMsg | TODO |
RelativeAngularAccel | TODO |
RelativeAngularVel | TODO |
RelativeLinearAccel | TODO |
RelativeLinearVel | TODO |
RelativePose | TODO |
SDFPoseRelativeToParent | TODO |
SDFSemanticPose | TODO |
Scale | TODO |
SensorScopedName | TODO |
SetAngularVel | TODO |
SetAnimation | TODO |
SetAutoDisable | TODO |
SetCollideMode | TODO |
SetEnabled | TODO |
SetGravityMode | TODO |
SetInitialRelativePose | TODO |
SetJointAnimation | TODO |
SetJointPosition | See joint API |
SetJointPositions | See joint API |
SetLaserRetro | TODO |
SetLinearVel | TODO |
SetLinkWorldPose | See link API |
SetName | TODO |
SetRelativePose | TODO |
SetSaveable | Not supported |
SetScale | TODO |
SetSelected | Selection is client-specific, not porting |
SetSelfCollide | TODO |
SetState | TODO |
SetStatic | TODO |
SetWindMode | TODO |
SetWorldPose | gz::sim::Model::SetWorldPoseCmd |
SetWorldTwist | TODO |
StopAnimation | TODO |
TypeStr | gz::sim::entityTypeStr |
URI | TODO |
UnscaledSDF | TODO |
UpdateParameters | TODO |
WindMode | gz::sim::Model::WindMode |
WorldAngularAccel | TODO |
WorldAngularVel | TODO |
WorldLinearAccel | TODO |
WorldLinearVel | TODO |
WorldPose | gz::sim::worldPose |
Read family
These APIs deal with reading information related to child / parent relationships.
The main difference in these APIs across Gazebo generations is that on classic, they deal with shared pointers to entities, while on Ignition, they deal with entity IDs.
Classic | Ignition |
---|---|
GetByName | Use type-specific gz::sim::Model::*ByName |
GetChild | Use type-specific gz::sim::Model::*ByName |
GetChildCollision | See link API |
GetChildCount | Use type-specific gz::sim::Model::*Count |
GetChildLink | gz::sim::Model::LinkByName |
GetGripper | TODO |
GetGripperCount | TODO |
GetJoint | gz::sim::Model::JointByName |
GetJointCount | gz::sim::Model::JointCount |
GetJoints | gz::sim::Model::Joints |
GetLink | gz::sim::Model::LinkByName |
GetLinks | const gz::sim::Model::Links |
GetParent | gz::sim::EntiyComponentManager::ParentEntity |
GetParentId | gz::sim::EntiyComponentManager::ParentEntity |
GetParentModel | gz::sim::EntiyComponentManager::ParentEntity |
GetSensorCount | See link API |
GetWorld | const gz::sim::Model::World |
NestedModel | gz::sim::Model::NestedModelByName |
NestedModels | const gz::sim::Model::NestedModels |
Write family
These functions deal with modifying the entity tree, attaching children to new parents.
Classic | Ignition |
---|---|
AddChild | TODO |
AttachStaticModel | TODO |
CreateJoint | TODO |
CreateLink | TODO |
DetachStaticModel | TODO |
RemoveChild | TODO |
RemoveChildren | TODO |
RemoveJoint | TODO |
SetCanonicalLink | TODO |
SetParent | TODO |
SetWorld | TODO |
Lifecycle
These functions aren't related to the state of a model, but perform some processing related to the model's lifecycle, like initializing, updating or terminating it.
Classic | Ignition |
---|---|
Fini | N/A |
Init | N/A |
Load | gz::sim::SdfEntityCreator::CreateEntities |
LoadJoints | gz::sim::SdfEntityCreator::CreateEntities |
LoadPlugins | TODO |
Reset | TODO |
ResetPhysicsStates | TODO |
Update | Entities are updated by systems |
Others
Miscelaneous functions that don't fit the other categories. Most of them involve logic that should be performed from within a system.
Classic | Ignition |
---|---|
GetJointController | Use this system: gz::sim::systems::JointController |
GetNearestEntityBelow | Requires a system |
PlaceOnEntity | Involves Requires a system |
PlaceOnNearestEntityBelow | Requires a system |