Skip to content
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

Added additional pose offset for the performer detector #236

Merged
merged 6 commits into from
Jul 13, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@
JointStatePublisher.
* [Pull Request 222](https:/ignitionrobotics/ign-gazebo/pull/222)

1. Added an additional pose offset for the performer detector plugin.
* [Pull Request 235](https:/ignitionrobotics/ign-gazebo/pull/235)
nkoenig marked this conversation as resolved.
Show resolved Hide resolved

### Ignition Gazebo 2.20.1 (2020-06-18)

1. Properly add new models into the scenegraph. With this fix, when a model is spawned it will be added into the graph and resulting calls to the `scene/info` service will return a correct `msgs::Scene`.
Expand Down
8 changes: 7 additions & 1 deletion src/systems/performer_detector/PerformerDetector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,11 @@ void PerformerDetector::Configure(const Entity &_entity,
return;
}

if (sdfClone->HasElement("pose"))
{
this->poseOffset = sdfClone->Get<math::Pose3d>("pose");
}

std::string defaultTopic{"/model/" + this->model.Name(_ecm) +
"/performer_detector/status"};
auto topic = _sdf->Get<std::string>("topic", defaultTopic).first;
Expand Down Expand Up @@ -109,7 +114,8 @@ void PerformerDetector::PostUpdate(

// Double negative because AxisAlignedBox does not currently have operator+
// that takes a position
auto region = this->detectorGeometry - (-modelPose.Pos());
auto region = this->detectorGeometry -
(-(modelPose.Pos() + this->poseOffset.Pos()));
azeey marked this conversation as resolved.
Show resolved Hide resolved

_ecm.Each<components::Performer, components::Geometry,
components::ParentEntity>(
Expand Down
5 changes: 5 additions & 0 deletions src/systems/performer_detector/PerformerDetector.hh
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,8 @@ namespace systems
/// `<geometry>`: Detection region. Currently, only the `<box>` geometry is
/// supported. The position of the geometry is derived from the pose of the
/// containing model.
/// `<pose>`: Additional pose offset. This pose is added to the parent
azeey marked this conversation as resolved.
Show resolved Hide resolved
/// model pose when computing the detection region.
nkoenig marked this conversation as resolved.
Show resolved Hide resolved

class IGNITION_GAZEBO_VISIBLE PerformerDetector
: public System,
Expand Down Expand Up @@ -128,6 +130,9 @@ namespace systems

/// \brief Whether the system has been initialized
private: bool initialized{false};

/// \brief Additional pose offset for the plugin.
private: math::Pose3d poseOffset;
};

}
Expand Down