Skip to content

Commit

Permalink
Ensure the model base link is set to the correct model
Browse files Browse the repository at this point in the history
- Set the link for the IMU contained in this model - the ECM foreach iterates over all model components in the world.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Jan 19, 2022
1 parent 10ea0ef commit a805ef2
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion src/ArduPilotPlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -764,7 +764,6 @@ void ignition::gazebo::systems::ArduPilotPlugin::PreUpdate(
{
// The parent of the imu is imu_link
ignition::gazebo::Entity parent = _ecm.ParentEntity(_imu_entity);
this->dataPtr->modelLink = parent;
if (parent != ignition::gazebo::kNullEntity)
{
// The grandparent of the imu is the quad itself, which is where this plugin is attached
Expand All @@ -774,6 +773,7 @@ void ignition::gazebo::systems::ArduPilotPlugin::PreUpdate(
ignition::gazebo::Model gparent_model(gparent);
if (gparent_model.Name(_ecm) == this->dataPtr->modelName)
{
this->dataPtr->modelLink = parent;
imuTopicName = ignition::gazebo::scopedName(_imu_entity, _ecm) + "/imu";
igndbg << "Computed IMU topic to be: " << imuTopicName << std::endl;
}
Expand Down

0 comments on commit a805ef2

Please sign in to comment.