Skip to content

Commit

Permalink
Fix more Animation memory leak (#98)
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <ichen@osrfoundation.org>
  • Loading branch information
iche033 authored Sep 28, 2020
1 parent 053083e commit 335aa84
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
2 changes: 1 addition & 1 deletion graphics/include/ignition/common/Animation.hh
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ namespace ignition
protected: bool loop;

/// \brief array of keyframe type alias
protected: typedef std::vector<common::KeyFrame*> KeyFrame_V;
protected: typedef std::vector<common::KeyFrame *> KeyFrame_V;

/// \brief array of key frames
protected: KeyFrame_V keyFrames;
Expand Down
9 changes: 6 additions & 3 deletions graphics/src/Animation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ class ignition::common::TrajectoryInfoPrivate
/// \brief Waypoints in pose animation format.
/// Times within the animation should be considered durations counted
/// from start time.
public: common::PoseAnimation *waypoints{nullptr};
public: std::shared_ptr<common::PoseAnimation> waypoints;

/// \brief Distance on the XY plane covered by each segment. The key is the
/// duration from start time, the value is the distance in meters.
Expand Down Expand Up @@ -262,6 +262,8 @@ PoseAnimation::~PoseAnimation()
{
delete this->positionSpline;
delete this->rotationSpline;
for (auto kf : this->keyFrames)
delete kf;
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -536,7 +538,7 @@ void TrajectoryInfo::SetTranslated(bool _translated)
/////////////////////////////////////////////////
common::PoseAnimation *TrajectoryInfo::Waypoints() const
{
return this->dataPtr->waypoints;
return this->dataPtr->waypoints.get();
}

/////////////////////////////////////////////////
Expand All @@ -553,7 +555,8 @@ void TrajectoryInfo::SetWaypoints(

std::stringstream animName;
animName << this->AnimIndex() << "_" << this->Id();
common::PoseAnimation *anim = new common::PoseAnimation(animName.str(),
std::shared_ptr<common::PoseAnimation> anim =
std::make_shared<common::PoseAnimation>(animName.str(),
std::chrono::duration<double>(this->Duration()).count(), false);

auto prevPose = first->second.Pos();
Expand Down
19 changes: 8 additions & 11 deletions graphics/src/SkeletonAnimation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class ignition::common::SkeletonAnimationPrivate
public: double length;

/// \brief a dictionary of node animations
public: std::map<std::string, NodeAnimation*> animations;
public: std::map<std::string, std::shared_ptr<NodeAnimation>> animations;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -74,7 +74,7 @@ NodeAnimation *SkeletonAnimation::NodeAnimationByName(
{
auto it = this->data->animations.find(_node);
if (it != this->data->animations.end())
return it->second;
return it->second.get();
return nullptr;
}

Expand All @@ -89,7 +89,7 @@ void SkeletonAnimation::AddKeyFrame(const std::string &_node,
const double _time, const math::Matrix4d &_mat)
{
if (this->data->animations.find(_node) == this->data->animations.end())
this->data->animations[_node] = new NodeAnimation(_node);
this->data->animations[_node] = std::make_shared<NodeAnimation>(_node);

if (_time > this->data->length)
this->data->length = _time;
Expand All @@ -102,7 +102,7 @@ void SkeletonAnimation::AddKeyFrame(const std::string &_node,
const double _time, const math::Pose3d &_pose)
{
if (this->data->animations.find(_node) == this->data->animations.end())
this->data->animations[_node] = new NodeAnimation(_node);
this->data->animations[_node] = std::make_shared<NodeAnimation>(_node);

if (_time > this->data->length)
this->data->length = _time;
Expand Down Expand Up @@ -133,9 +133,8 @@ std::map<std::string, math::Matrix4d> SkeletonAnimation::PoseAt(
/// prev and next keyframe for each node at each time step, but rather
/// doing it only once per time step.
std::map<std::string, math::Matrix4d> pose;
for (std::map<std::string, NodeAnimation*>::const_iterator iter =
this->data->animations.begin();
iter != this->data->animations.end(); ++iter)
for (auto iter = this->data->animations.begin();
iter != this->data->animations.end(); ++iter)
{
pose[iter->first] = iter->second->FrameAt(_time, _loop);
}
Expand All @@ -147,8 +146,7 @@ std::map<std::string, math::Matrix4d> SkeletonAnimation::PoseAt(
std::map<std::string, math::Matrix4d> SkeletonAnimation::PoseAtX(
const double _x, const std::string &_node, const bool _loop) const
{
std::map<std::string, NodeAnimation*>::const_iterator nodeAnim =
this->data->animations.find(_node);
auto nodeAnim = this->data->animations.find(_node);
if (nodeAnim == this->data->animations.end())
{
ignerr << "Can't find animation named [" << _node << "]" << std::endl;
Expand Down Expand Up @@ -178,8 +176,7 @@ std::map<std::string, math::Matrix4d> SkeletonAnimation::PoseAtX(
//////////////////////////////////////////////////
void SkeletonAnimation::Scale(const double _scale)
{
for (std::map<std::string, NodeAnimation*>::iterator iter =
this->data->animations.begin();
for (auto iter = this->data->animations.begin();
iter != this->data->animations.end(); ++iter)
{
iter->second->Scale(_scale);
Expand Down

0 comments on commit 335aa84

Please sign in to comment.