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

Fix crash in the follow_actor example #958

Merged
merged 9 commits into from
Aug 12, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
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
26 changes: 18 additions & 8 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -356,9 +356,14 @@ class ignition::gazebo::RenderUtilPrivate
/// RenderUtil::Update.
/// \param[in] _actorAnimationData A map of entities to their animation update
/// data.
/// \param[in] _entityPoses A map of entity ids and pose updates.
/// \param[in] _trajectoryPoses A map of entity ids and trajectory
/// pose updates.
/// \sa actorManualSkeletonUpdate
public: void UpdateAnimation(const std::unordered_map<Entity,
AnimationUpdateData> &_actorAnimationData);
AnimationUpdateData> &_actorAnimationData,
const std::unordered_map<Entity, math::Pose3d> &_entityPoses,
const std::unordered_map<Entity, math::Pose3d> &_trajectoryPoses);
adlarkin marked this conversation as resolved.
Show resolved Hide resolved
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -804,7 +809,8 @@ void RenderUtil::Update()
}
else
{
this->dataPtr->UpdateAnimation(actorAnimationData);
this->dataPtr->UpdateAnimation(actorAnimationData, entityPoses,
trajectoryPoses);
}
}

Expand Down Expand Up @@ -2028,8 +2034,10 @@ void RenderUtilPrivate::UpdateThermalCamera(const std::unordered_map<Entity,
}

/////////////////////////////////////////////////
void RenderUtilPrivate::UpdateAnimation(
const std::unordered_map<Entity, AnimationUpdateData> &_actorAnimationData)
void RenderUtilPrivate::UpdateAnimation(const std::unordered_map<Entity,
AnimationUpdateData> &_actorAnimationData,
const std::unordered_map<Entity, math::Pose3d> &_entityPoses,
const std::unordered_map<Entity, math::Pose3d> &_trajectoryPoses)
{
for (auto &it : _actorAnimationData)
{
Expand Down Expand Up @@ -2098,16 +2106,18 @@ void RenderUtilPrivate::UpdateAnimation(

// update actor trajectory animation
math::Pose3d globalPose;
if (entityPoses.find(it.first) != entityPoses.end())
auto entityPosesIt = _entityPoses.find(it.first);
if (entityPosesIt != _entityPoses.end())
{
globalPose = entityPoses[it.first];
globalPose = entityPosesIt->second;
}

math::Pose3d trajPose;
// Trajectory from the ECS
if (trajectoryPoses.find(it.first) != trajectoryPoses.end())
auto trajectoryPosesIt = _trajectoryPoses.find(it.first);
if (trajectoryPosesIt != _trajectoryPoses.end())
{
trajPose = trajectoryPoses[it.first];
trajPose = trajectoryPosesIt->second;
}
else
{
Expand Down
3 changes: 2 additions & 1 deletion test/integration/follow_actor_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtest/gtest.h>
#include <ignition/common/Console.hh>
#include <ignition/math/Pose3.hh>
#include <ignition/utilities/ExtraTestMacros.hh>

#include "ignition/gazebo/components/Actor.hh"
#include "ignition/gazebo/components/Name.hh"
Expand Down Expand Up @@ -88,7 +89,7 @@ class Relay


/////////////////////////////////////////////////
TEST_P(FollowActorTest, PublishCmd)
TEST_P(FollowActorTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PublishCmd))
{
// Start server
ServerConfig serverConfig;
Expand Down
40 changes: 40 additions & 0 deletions test/worlds/follow_actor.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,46 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="actors">

<!-- add sensors system and camera so that the rendering code is also tested
-->
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<model name="camera">
<static>true</static>
<pose>0 0 0 0 0 0</pose>
<link name="link">
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<pose>1 0 1.3 0 0 0</pose>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>camera</topic>
</sensor>
</link>
</model>

<model name="box">
<static>true</static>
<pose>1 -2 0.5 0 0 0</pose>
Expand Down