Skip to content

Commit

Permalink
Merged in skel_animation (pull request #579)
Browse files Browse the repository at this point in the history
Actor skeleton animation (auto update mode)

Approved-by: Louise Poubel <[email protected]>
  • Loading branch information
iche033 committed Apr 11, 2020
2 parents be0338d + b353d09 commit d66df33
Show file tree
Hide file tree
Showing 10 changed files with 1,434 additions and 129 deletions.
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@

### Ignition Gazebo 4.0.0 (20XX-XX-XX)

1. Actor skeleton animation (auto update mode)
* [Pull Request 579](https://bitbucket.org/ignitionrobotics/ign-gazebo/pull-requests/579)

1. Added support for removing sensors at runtime
* [Pull Request 558](https://bitbucket.org/ignitionrobotics/ign-gazebo/pull-requests/558)

Expand Down
49 changes: 44 additions & 5 deletions examples/plugin/command_actor/CommandActor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,11 @@ void CommandActor::Configure(const ignition::gazebo::Entity &_entity,
ignmsg << "Command actor for entity [" << _entity << "]" << std::endl;

auto sdfClone = _sdf->Clone();

// Origin demo
for (auto originElem = sdfClone->GetElement("origin");
originElem != nullptr;
originElem = originElem->GetNextElement())
originElem = originElem->GetNextElement("origin"))
{
auto pose = originElem->Get<ignition::math::Pose3d>("pose");
auto time = originElem->Get<int>("time");
Expand All @@ -57,6 +59,20 @@ void CommandActor::Configure(const ignition::gazebo::Entity &_entity,
ignmsg << "Stored origin change at [" << time << "] seconds to pose ["
<< pose << "]" << std::endl;
}

// Trajectory pose demo
for (auto trajPoseElem = sdfClone->GetElement("trajectory_pose");
trajPoseElem != nullptr;
trajPoseElem = trajPoseElem->GetNextElement("trajectory_pose"))
{
auto pose = trajPoseElem->Get<ignition::math::Pose3d>("pose");
auto time = trajPoseElem->Get<int>("time");

this->trajPoses[time] = pose;
ignmsg << "Stored trajectory pose change at [" << time
<< "] seconds to pose ["
<< pose << "]" << std::endl;
}
}

//////////////////////////////////////////////////
Expand All @@ -66,10 +82,9 @@ void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
auto sec = std::chrono::duration_cast<std::chrono::seconds>(
_info.simTime).count();

if (sec <= this->lastOriginChange)
return;

if (this->origins.find(sec) != this->origins.end())
// Update origins
if (sec > this->lastOriginChange &&
this->origins.find(sec) != this->origins.end())
{
auto poseComp = _ecm.Component<ignition::gazebo::components::Pose>(
this->entity);
Expand All @@ -84,4 +99,28 @@ void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info,

this->lastOriginChange = sec;
}

// Update trajectory poses
if (sec > this->lastTrajPoseChange &&
this->trajPoses.find(sec) != this->trajPoses.end())
{
auto trajPoseComp =
_ecm.Component<ignition::gazebo::components::TrajectoryPose>(
this->entity);
if (nullptr == trajPoseComp)
{
_ecm.CreateComponent(this->entity,
ignition::gazebo::components::TrajectoryPose(this->trajPoses[sec]));
}
else
{
*trajPoseComp =
ignition::gazebo::components::TrajectoryPose(this->trajPoses[sec]);
}

ignmsg << "Changing trajectory pose to [" << this->trajPoses[sec] << "]"
<< std::endl;

this->lastTrajPoseChange = sec;
}
}
16 changes: 13 additions & 3 deletions examples/plugin/command_actor/CommandActor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,24 @@ namespace command_actor
public: void PreUpdate(const ignition::gazebo::UpdateInfo &_info,
ignition::gazebo::EntityComponentManager &_ecm) override;

// Actor entity
/// \brief Actor entity
private: ignition::gazebo::Entity entity;

// Origins to change, where the key is the number of seconds from beginning
// of simulation, and the value is the new trajectory origin to set.
/// \brief Origins to change, where the key is the number of seconds from
/// beginning of simulation, and the value is the new trajectory origin to
/// set.
private: std::map<int, ignition::math::Pose3d> origins;

/// \brief Trajectory poses to change, where the key is the number of
/// seconds from beginning of simulation, and the value is the new
/// trajectory pose to set.
private: std::map<int, ignition::math::Pose3d> trajPoses;

/// \brief Last time, in seconds, when the origin was changed.
private: int lastOriginChange{0};

/// \brief Last time, in seconds, when the trajectory pose was changed.
private: int lastTrajPoseChange{0};
};
}

Expand Down
9 changes: 9 additions & 0 deletions examples/plugin/command_actor/command_actor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,15 @@
<time>5</time>
<pose>10 10 0 0 0 0</pose>
</origin>

<!--
At 10 seconds sim time, fix the trajectory pose to a given value.
This disables the waypoints from SDF.
-->
<trajectory_pose>
<time>10</time>
<pose>-5 -5 1 0 0 0</pose>
</trajectory_pose>
</plugin>
</include>
</world>
Expand Down
4 changes: 2 additions & 2 deletions examples/worlds/actor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<plugin
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre</render_engine>
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
Expand All @@ -31,7 +31,7 @@
<property type="string" key="state">docked</property>
</ignition-gui>

<engine>ogre</engine>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
Expand Down
Loading

0 comments on commit d66df33

Please sign in to comment.