From 3007d7ad923dad5984102b0b228e295111b439cc Mon Sep 17 00:00:00 2001 From: chapulina Date: Thu, 5 Mar 2020 18:09:32 -0800 Subject: [PATCH 01/19] add trajectory pose --- examples/plugin/command_actor/CommandActor.cc | 49 +++++++++++++++++-- examples/plugin/command_actor/CommandActor.hh | 16 ++++-- .../plugin/command_actor/command_actor.sdf | 9 ++++ include/ignition/gazebo/components/Pose.hh | 6 +++ src/rendering/RenderUtil.cc | 30 ++++++++++-- 5 files changed, 99 insertions(+), 11 deletions(-) diff --git a/examples/plugin/command_actor/CommandActor.cc b/examples/plugin/command_actor/CommandActor.cc index c2f10ace1c..82ad0d2150 100644 --- a/examples/plugin/command_actor/CommandActor.cc +++ b/examples/plugin/command_actor/CommandActor.cc @@ -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("pose"); auto time = originElem->Get("time"); @@ -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("pose"); + auto time = trajPoseElem->Get("time"); + + this->trajPoses[time] = pose; + ignmsg << "Stored trajectory pose change at [" << time + << "] seconds to pose [" + << pose << "]" << std::endl; + } } ////////////////////////////////////////////////// @@ -66,10 +82,9 @@ void CommandActor::PreUpdate(const ignition::gazebo::UpdateInfo &_info, auto sec = std::chrono::duration_cast( _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( this->entity); @@ -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( + 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; + } } diff --git a/examples/plugin/command_actor/CommandActor.hh b/examples/plugin/command_actor/CommandActor.hh index 6c53c35a1b..124a9914df 100644 --- a/examples/plugin/command_actor/CommandActor.hh +++ b/examples/plugin/command_actor/CommandActor.hh @@ -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 origins; + /// \brief Trajecotry 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 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}; }; } diff --git a/examples/plugin/command_actor/command_actor.sdf b/examples/plugin/command_actor/command_actor.sdf index 3fe408156e..7bdf9d6417 100644 --- a/examples/plugin/command_actor/command_actor.sdf +++ b/examples/plugin/command_actor/command_actor.sdf @@ -129,6 +129,15 @@ 10 10 0 0 0 0 + + + + + -5 -5 1 0 0 0 + diff --git a/include/ignition/gazebo/components/Pose.hh b/include/ignition/gazebo/components/Pose.hh index 96b8626442..b07faff7da 100644 --- a/include/ignition/gazebo/components/Pose.hh +++ b/include/ignition/gazebo/components/Pose.hh @@ -40,6 +40,12 @@ namespace components using WorldPose = Component; IGN_GAZEBO_REGISTER_COMPONENT( "ign_gazebo_components.WorldPose", WorldPose) + + /// \brief A component type that contains pose, ignition::math::Pose3d, + /// information within a trajectory. + using TrajectoryPose = Component; + IGN_GAZEBO_REGISTER_COMPONENT( + "ign_gazebo_components.TrajectoryPose", TrajectoryPose) } } } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 8cd0e6deb7..a04f4d3171 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -163,6 +163,9 @@ class ignition::gazebo::RenderUtilPrivate public: std::map> actorTransforms; + /// \brief A map of entity ids and trajectory pose updates. + public: std::map trajectoryPoses; + /// \brief Mutex to protect updates public: std::mutex updateMutex; @@ -246,6 +249,7 @@ void RenderUtil::Update() auto newLights = std::move(this->dataPtr->newLights); auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); + auto trajectoryPoses = std::move(this->dataPtr->trajectoryPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); this->dataPtr->newScenes.clear(); @@ -256,6 +260,7 @@ void RenderUtil::Update() this->dataPtr->newLights.clear(); this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); + this->dataPtr->trajectoryPoses.clear(); this->dataPtr->actorTransforms.clear(); this->dataPtr->markerManager.Update(); @@ -381,7 +386,7 @@ void RenderUtil::Update() // update entities' pose { IGN_PROFILE("RenderUtil::Update Poses"); - for (auto &pose : entityPoses) + for (const auto &pose : entityPoses) { auto node = this->dataPtr->sceneManager.NodeById(pose.first); if (!node) @@ -413,8 +418,18 @@ void RenderUtil::Update() } math::Pose3d trajPose; - trajPose.Pos() = tf.second["actorPose"].Translation(); - trajPose.Rot() = tf.second["actorPose"].Rotation(); + // Trajectory from the ECS + if (trajectoryPoses.find(tf.first) != trajectoryPoses.end()) + { + trajPose = trajectoryPoses[tf.first]; + } + // Trajectory from the SDF script + else + { + trajPose.Pos() = tf.second["actorPose"].Translation(); + trajPose.Rot() = tf.second["actorPose"].Rotation(); + } + actorVisual->SetLocalPose(trajPose + globalPose); tf.second.erase("actorPose"); @@ -793,9 +808,18 @@ void RenderUtilPrivate::UpdateRenderingEntities( const components::Actor *, const components::Pose *_pose)->bool { + // Trajectory origin this->entityPoses[_entity] = _pose->Data(); + + // Bone poses calculated by ign-common this->actorTransforms[_entity] = this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + + // Trajectory pose set by other systems + auto trajPoseComp = _ecm.Component(_entity); + if (trajPoseComp) + this->trajectoryPoses[_entity] = trajPoseComp->Data(); + return true; }); From db38d81aeeb13ecee360b43070e5092568afcce5 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 12 Mar 2020 13:33:31 -0700 Subject: [PATCH 02/19] WIP skel animation. Refactored traj animation --- .../ignition/gazebo/rendering/SceneManager.hh | 12 +++ src/rendering/RenderUtil.cc | 69 +++++++++---- src/rendering/SceneManager.cc | 99 +++++++++++++------ 3 files changed, 132 insertions(+), 48 deletions(-) diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 192732370a..721e45f7e8 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -31,6 +31,7 @@ #include #include +#include #include @@ -133,6 +134,17 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \return Pointer to requested entity's mesh public: rendering::MeshPtr ActorMeshById(Entity _id) const; + /// \brief Get the trajectory at input time and returns animation time + /// associated with the trajectory. + /// \param[in] _id Entity's unique id + /// \param[in] _time Timepoint for the animation + /// \param[out] Trajectory of actor at specified time. + /// \return Update time. + public: std::chrono::steady_clock::duration ActorTrajectoryAt( + Entity _id, const std::chrono::steady_clock::duration &_time, + common::TrajectoryInfo &_traj) const; + + /// \brief Get the animation of actor mesh given an id /// \param[in] _id Entity's unique id /// \param[in] _time Timepoint for the animation diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 8cd0e6deb7..b8b5ca4f9c 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -163,6 +163,15 @@ class ignition::gazebo::RenderUtilPrivate public: std::map> actorTransforms; + /// \brief A map of entity ids and actor animation time. + public: std::map + actorAnimationTimes; + + /// \brief True to update skeletons manually using bone poses + /// (see actorTransforms). False to let render engine update animation + /// based on sim time. + public: bool actorManualSkeletonUpdate = true; + /// \brief Mutex to protect updates public: std::mutex updateMutex; @@ -247,6 +256,7 @@ void RenderUtil::Update() auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); + auto actorAnimationTime = std::move(this->dataPtr->actorAnimationTimes); this->dataPtr->newScenes.clear(); this->dataPtr->newModels.clear(); @@ -257,6 +267,7 @@ void RenderUtil::Update() this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); this->dataPtr->actorTransforms.clear(); + this->dataPtr->actorAnimationTimes.clear(); this->dataPtr->markerManager.Update(); @@ -399,26 +410,34 @@ void RenderUtil::Update() } // update entities' local transformations - for (auto &tf : actorTransforms) + if (this->dataPtr->actorManualSkeletonUpdate) { - auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(tf.first); - auto actorVisual = this->dataPtr->sceneManager.NodeById(tf.first); - if (!actorMesh || !actorVisual) - continue; - - math::Pose3d globalPose; - if (entityPoses.find(tf.first) != entityPoses.end()) + for (auto &tf : actorTransforms) { - globalPose = entityPoses[tf.first]; - } + auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(tf.first); + auto actorVisual = this->dataPtr->sceneManager.NodeById(tf.first); + if (!actorMesh || !actorVisual) + continue; - math::Pose3d trajPose; - trajPose.Pos() = tf.second["actorPose"].Translation(); - trajPose.Rot() = tf.second["actorPose"].Rotation(); - actorVisual->SetLocalPose(trajPose + globalPose); + math::Pose3d actorPose; + actorPose.Pos() = tf.second["actorPose"].Translation(); + actorPose.Rot() = tf.second["actorPose"].Rotation(); + actorVisual->SetLocalPose(actorPose); - tf.second.erase("actorPose"); - actorMesh->SetSkeletonLocalTransforms(tf.second); + tf.second.erase("actorPose"); + actorMesh->SetSkeletonLocalTransforms(tf.second); + } + } + else + { + for (auto &it : this->dataPtr->actorAnimationTimes) + { + auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(it.first); + auto actorVisual = this->dataPtr->sceneManager.NodeById(it.first); + if (!actorMesh || !actorVisual) + continue; + actorMesh->UpdateSkeletonAnimation(it.second); + } } } } @@ -791,11 +810,21 @@ void RenderUtilPrivate::UpdateRenderingEntities( _ecm.Each( [&](const Entity &_entity, const components::Actor *, - const components::Pose *_pose)->bool + const components::Pose *)->bool { - this->entityPoses[_entity] = _pose->Data(); - this->actorTransforms[_entity] = - this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + // TODO(anyone) Support setting actor pose from other systems + // this->entityPoses[_entity] = _pose->Data(); + + if (this->actorManualSkeletonUpdate) + { + this->actorTransforms[_entity] = + this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + } + else + { +// this->actorAnimationTimes[_entity] = +// this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + } return true; }); diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 24e9ded6eb..7baaf27621 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -45,6 +45,8 @@ using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; +using TP = std::chrono::steady_clock::time_point; + /// \brief Private data class. class ignition::gazebo::SceneManagerPrivate { @@ -587,7 +589,6 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, } this->dataPtr->actorSkeletons[_id] = meshSkel; - using TP = std::chrono::steady_clock::time_point; std::vector trajectories; if (_actor.TrajectoryCount() != 0) @@ -842,18 +843,27 @@ rendering::MeshPtr SceneManager::ActorMeshById(Entity _id) const } ///////////////////////////////////////////////// -std::map SceneManager::ActorMeshAnimationAt( - Entity _id, std::chrono::steady_clock::duration _time) const -{ - std::map allFrames; +// bool SceneManager::CorrectTime( +// const std::vector &_trajs, +// std::chrono::steady_clock::duration &_time) const +// { +// +// } - if (this->dataPtr->actorTrajectories.find(_id) - == this->dataPtr->actorTrajectories.end()) +///////////////////////////////////////////////// +std::chrono::steady_clock::duration SceneManager::ActorTrajectoryAt( + Entity _id, + const std::chrono::steady_clock::duration &_time, + common::TrajectoryInfo &_traj) const +{ + _traj.SetId(-1); + auto trajIt = this->dataPtr->actorTrajectories.find(_id); + if (trajIt == this->dataPtr->actorTrajectories.end()) { - return allFrames; + return _time; } - auto trajs = this->dataPtr->actorTrajectories[_id]; + auto trajs = trajIt->second; bool followTraj = true; if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) { @@ -861,55 +871,88 @@ std::map SceneManager::ActorMeshAnimationAt( } auto firstTraj = trajs.begin(); - auto poseFrame = common::PoseKeyFrame(0.0); - common::TrajectoryInfo traj = trajs[0]; + _traj = trajs[0]; - using TP = std::chrono::steady_clock::time_point; +// using TP = std::chrono::steady_clock::time_point; auto totalTime = trajs.rbegin()->EndTime() - trajs.begin()->StartTime(); // delay start - if (_time < (trajs.begin()->StartTime() - TP(0ms))) + auto time = _time; + if (time < (trajs.begin()->StartTime() - TP(0ms))) { - _time = std::chrono::steady_clock::duration(0); + time = std::chrono::steady_clock::duration(0); } else { - _time -= trajs.begin()->StartTime() - TP(0ms); + time -= trajs.begin()->StartTime() - TP(0ms); } bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); - if (_time >= totalTime && noLoop) + if (time >= totalTime && noLoop) { - _time = totalTime; + time = totalTime; } - if (!noLoop || _time <= totalTime) +// auto poseFrame = common::PoseKeyFrame(0.0); + if (!noLoop || time <= totalTime) { - while (_time > totalTime) + while (time > totalTime) { - _time = _time - totalTime; + time = time - totalTime; } if (followTraj) { for (auto &trajectory : trajs) { - if (trajectory.StartTime() - firstTraj->StartTime() <= _time - && trajectory.EndTime() - firstTraj->StartTime() >= _time) + if (trajectory.StartTime() - firstTraj->StartTime() <= time + && trajectory.EndTime() - firstTraj->StartTime() >= time) { - traj = trajectory; - _time -= traj.StartTime() - firstTraj->StartTime(); + _traj = trajectory; + time -= _traj.StartTime() - firstTraj->StartTime(); - traj.Waypoints()->Time(std::chrono::duration(_time).count()); - traj.Waypoints()->InterpolatedKeyFrame(poseFrame); + _traj.Waypoints()->Time(std::chrono::duration(time).count()); break; } } } } + return time; +} + +///////////////////////////////////////////////// +std::map SceneManager::ActorMeshAnimationAt( + Entity _id, std::chrono::steady_clock::duration _time) const +{ + std::map allFrames; + auto trajIt = this->dataPtr->actorTrajectories.find(_id); + if (trajIt == this->dataPtr->actorTrajectories.end()) + { + return allFrames; + } + + // get the trajectory at input time + // The time returned is the time at which the animation should be played + common::TrajectoryInfo traj; + auto time = this->ActorTrajectoryAt(_id, _time, traj); + + auto trajs = trajIt->second; + bool followTraj = true; + if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) + { + followTraj = false; + } + + bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) + && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); + + + common::PoseKeyFrame poseFrame(0.0); + if (followTraj) + traj.Waypoints()->InterpolatedKeyFrame(poseFrame); math::Matrix4d rootTf(poseFrame.Rotation()); rootTf.SetTranslation(poseFrame.Translation()); @@ -920,11 +963,11 @@ std::map SceneManager::ActorMeshAnimationAt( unsigned int animIndex = traj.AnimIndex(); std::map rawFrames; - double timeSeconds = std::chrono::duration(_time).count(); + double timeSeconds = std::chrono::duration(time).count(); if (followTraj) { - double distance = traj.DistanceSoFar(_time); + double distance = traj.DistanceSoFar(time); if (distance < 0.1) { rawFrames = skel->Animation(animIndex)->PoseAt(timeSeconds, !noLoop); From b350e69d57a9c72c6879d0f91fae077eea56994c Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 23 Mar 2020 12:19:32 -0700 Subject: [PATCH 03/19] add anim info --- .../ignition/gazebo/rendering/SceneManager.hh | 24 ++++- src/rendering/RenderUtil.cc | 53 +++++++++-- src/rendering/SceneManager.cc | 92 +++++++++++++------ 3 files changed, 130 insertions(+), 39 deletions(-) diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 721e45f7e8..8769e9ebff 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -48,6 +48,17 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { // Forward declaration class SceneManagerPrivate; + /// \brief Scene manager class for loading and managing objects in the scene + class AnimInfo + { + public: std::chrono::steady_clock::duration time; + public: std::string name; + public: bool loop = false; + public: bool followTrajectory = false; + public: common::TrajectoryInfo trajectory; + public: bool valid = false; + }; + /// \brief Scene manager class for loading and managing objects in the scene class IGNITION_GAZEBO_VISIBLE SceneManager { @@ -140,9 +151,13 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _time Timepoint for the animation /// \param[out] Trajectory of actor at specified time. /// \return Update time. - public: std::chrono::steady_clock::duration ActorTrajectoryAt( - Entity _id, const std::chrono::steady_clock::duration &_time, - common::TrajectoryInfo &_traj) const; + // public: std::chrono::steady_clock::duration ActorTrajectoryAt( + // Entity _id, const std::chrono::steady_clock::duration &_time, + // common::TrajectoryInfo &_traj) const; + + + public: AnimInfo ActorTrajectoryAt( + Entity _id, const std::chrono::steady_clock::duration &_time) const; /// \brief Get the animation of actor mesh given an id @@ -152,6 +167,9 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: std::map ActorMeshAnimationAt( Entity _id, std::chrono::steady_clock::duration _time) const; + public: AnimInfo ActorAnimationAt( + Entity _id, std::chrono::steady_clock::duration _time) const; + /// \brief Remove an entity by id /// \param[in] _id Entity's unique id public: void RemoveEntity(Entity _id); diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index b8b5ca4f9c..034b204294 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -163,14 +163,15 @@ class ignition::gazebo::RenderUtilPrivate public: std::map> actorTransforms; - /// \brief A map of entity ids and actor animation time. - public: std::map - actorAnimationTimes; + /// \brief A map of entity ids and actor animation info. + public: std::map + actorAnimationInfo; + public: std::string prevAnimName; /// \brief True to update skeletons manually using bone poses /// (see actorTransforms). False to let render engine update animation /// based on sim time. - public: bool actorManualSkeletonUpdate = true; + public: bool actorManualSkeletonUpdate = false; /// \brief Mutex to protect updates public: std::mutex updateMutex; @@ -256,7 +257,7 @@ void RenderUtil::Update() auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); - auto actorAnimationTime = std::move(this->dataPtr->actorAnimationTimes); + auto actorAnimationInfo= std::move(this->dataPtr->actorAnimationInfo); this->dataPtr->newScenes.clear(); this->dataPtr->newModels.clear(); @@ -267,7 +268,7 @@ void RenderUtil::Update() this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); this->dataPtr->actorTransforms.clear(); - this->dataPtr->actorAnimationTimes.clear(); + this->dataPtr->actorAnimationInfo.clear(); this->dataPtr->markerManager.Update(); @@ -430,13 +431,45 @@ void RenderUtil::Update() } else { - for (auto &it : this->dataPtr->actorAnimationTimes) + for (auto &it : actorAnimationInfo) { auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(it.first); auto actorVisual = this->dataPtr->sceneManager.NodeById(it.first); if (!actorMesh || !actorVisual) continue; - actorMesh->UpdateSkeletonAnimation(it.second); + // actorMesh->UpdateSkeletonAnimation(it.second); + AnimInfo &info = it.second; + if (!info.valid) + { + ignerr << "invalid animation info" << std::endl; + continue; + } + // if (!actorMesh->SkeletonAnimationEnabled(info.name)) + // { + // // disable previous anim + // if (!this->dataPtr->prevAnimName.empty()) + // { + // actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->prevAnimName, + // false, false, 0.0); + // } + // // disable previous anim + // // actorMesh->SetSkeletonAnimationEnabled(info.name, true, info.loop); + // actorMesh->SetSkeletonAnimationEnabled(info.name, true, info.loop); + // this->dataPtr->prevAnimName = info.name; + // } + // actorMesh->UpdateSkeletonAnimation(info.time); + + double timeSeconds = std::chrono::duration(info.time).count(); + std::cerr << "info: " << info.name << " " << timeSeconds << std::endl; + + common::PoseKeyFrame poseFrame(0.0); + if (info.followTrajectory) + info.trajectory.Waypoints()->InterpolatedKeyFrame(poseFrame); + + math::Pose3d actorPose; + actorPose.Pos() = poseFrame.Translation(); + actorPose.Rot() = poseFrame.Rotation(); + actorVisual->SetLocalPose(actorPose); } } } @@ -822,8 +855,8 @@ void RenderUtilPrivate::UpdateRenderingEntities( } else { -// this->actorAnimationTimes[_entity] = -// this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + this->actorAnimationInfo[_entity] = + this->sceneManager.ActorAnimationAt(_entity, this->simTime); } return true; }); diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 7baaf27621..d3e067b091 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -851,28 +851,31 @@ rendering::MeshPtr SceneManager::ActorMeshById(Entity _id) const // } ///////////////////////////////////////////////// -std::chrono::steady_clock::duration SceneManager::ActorTrajectoryAt( +// std::chrono::steady_clock::duration SceneManager::ActorTrajectoryAt( +AnimInfo SceneManager::ActorTrajectoryAt( Entity _id, - const std::chrono::steady_clock::duration &_time, - common::TrajectoryInfo &_traj) const + const std::chrono::steady_clock::duration &_time) const { - _traj.SetId(-1); + // _traj.SetId(-1); + // auto trajIt = this->dataPtr->actorTrajectories.find(_id); + // if (trajIt == this->dataPtr->actorTrajectories.end()) + // { + // return _time; + // } + + AnimInfo info; auto trajIt = this->dataPtr->actorTrajectories.find(_id); if (trajIt == this->dataPtr->actorTrajectories.end()) - { - return _time; - } + return info; auto trajs = trajIt->second; bool followTraj = true; if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) - { followTraj = false; - } auto firstTraj = trajs.begin(); - _traj = trajs[0]; + common::TrajectoryInfo traj = trajs[0]; // using TP = std::chrono::steady_clock::time_point; auto totalTime = trajs.rbegin()->EndTime() - trajs.begin()->StartTime(); @@ -910,16 +913,48 @@ std::chrono::steady_clock::duration SceneManager::ActorTrajectoryAt( if (trajectory.StartTime() - firstTraj->StartTime() <= time && trajectory.EndTime() - firstTraj->StartTime() >= time) { - _traj = trajectory; - time -= _traj.StartTime() - firstTraj->StartTime(); + traj = trajectory; + time -= traj.StartTime() - firstTraj->StartTime(); - _traj.Waypoints()->Time(std::chrono::duration(time).count()); + traj.Waypoints()->Time(std::chrono::duration(time).count()); break; } } } } - return time; + + // return time; + info.time = time; + info.loop = !noLoop; + info.followTrajectory = followTraj; + info.trajectory = traj; + info.valid = true; + return info; +} + +///////////////////////////////////////////////// +AnimInfo SceneManager::ActorAnimationAt( + Entity _id, std::chrono::steady_clock::duration _time) const +{ + AnimInfo animInfo; + auto trajIt = this->dataPtr->actorTrajectories.find(_id); + if (trajIt == this->dataPtr->actorTrajectories.end()) + return animInfo; + + auto skelIt = this->dataPtr->actorSkeletons.find(_id); + if (skelIt == this->dataPtr->actorSkeletons.end()) + return animInfo; + + animInfo = this->ActorTrajectoryAt(_id, _time); + // bool followTraj = animInfo.followTrajectory; + // bool noLoop = animInfo.loop; + // common::TrajectoryInfo traj = animInfo.trajectory; + // auto time = animInfo.time; + + auto skel = skelIt->second; + unsigned int animIndex = animInfo.trajectory.AnimIndex(); + animInfo.name = skel->Animation(animIndex)->Name(); + return animInfo; } ///////////////////////////////////////////////// @@ -936,18 +971,23 @@ std::map SceneManager::ActorMeshAnimationAt( // get the trajectory at input time // The time returned is the time at which the animation should be played - common::TrajectoryInfo traj; - auto time = this->ActorTrajectoryAt(_id, _time, traj); - - auto trajs = trajIt->second; - bool followTraj = true; - if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) - { - followTraj = false; - } - - bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) - && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); + // common::TrajectoryInfo traj; + // auto time = this->ActorTrajectoryAt(_id, _time, traj); + AnimInfo animInfo = this->ActorTrajectoryAt(_id, _time); + bool followTraj = animInfo.followTrajectory; + bool noLoop = animInfo.loop; + common::TrajectoryInfo traj = animInfo.trajectory; + auto time = animInfo.time; + + // auto trajs = trajIt->second; + // bool followTraj = true; + // if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) + // { + // followTraj = false; + // } + + // bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) + // && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); common::PoseKeyFrame poseFrame(0.0); From 96e932f8daa41a9016c51cc46d177eb6c0556226 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 25 Mar 2020 13:57:41 -0700 Subject: [PATCH 04/19] skeleton animation working with traj --- examples/worlds/actor.sdf | 4 +- .../ignition/gazebo/rendering/SceneManager.hh | 69 +++-- src/rendering/RenderUtil.cc | 95 ++++-- src/rendering/SceneManager.cc | 290 ++++++++++-------- 4 files changed, 285 insertions(+), 173 deletions(-) diff --git a/examples/worlds/actor.sdf b/examples/worlds/actor.sdf index ac4e299315..77e34ab6a3 100644 --- a/examples/worlds/actor.sdf +++ b/examples/worlds/actor.sdf @@ -11,7 +11,7 @@ - ogre + ogre2 docked - ogre + ogre2 scene 0.4 0.4 0.4 0.8 0.8 0.8 diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 8769e9ebff..822d8c62f2 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -48,14 +48,37 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { // Forward declaration class SceneManagerPrivate; - /// \brief Scene manager class for loading and managing objects in the scene - class AnimInfo + /// \brief Data structure for updaing skeleton animations + class AnimationUpdateData { + /// \brief Timepoint in the animation. + /// Note that animation time is different from sim time. An actor can + /// have multiple animations. Animation time is associated with + /// current animation that is being played. This value is also adjusted if + /// interpotate_x is enabled public: std::chrono::steady_clock::duration time; - public: std::string name; + + /// \brief True if animation is looped public: bool loop = false; + + /// \brief True trajectory animation is on public: bool followTrajectory = false; + + /// \brief Trajectory to be followed public: common::TrajectoryInfo trajectory; + + /// \brief Name of animation to play. This field is set only if the actor + /// is not animated by manually using skeleton transforms + public: std::string animationName; + + /// \brief Transform of the root node in the skeleton. The actor's + /// skeleton's root node transform need to be set if trajectory + /// animation is enabled. This field is set only if the actor + /// is not animated by manually using skeleton transforms + public: math::Matrix4d rootTransform; + + /// \brief True if this animation update data is valid. If false, this + /// update data should be ignored public: bool valid = false; }; @@ -145,29 +168,37 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \return Pointer to requested entity's mesh public: rendering::MeshPtr ActorMeshById(Entity _id) const; - /// \brief Get the trajectory at input time and returns animation time - /// associated with the trajectory. - /// \param[in] _id Entity's unique id - /// \param[in] _time Timepoint for the animation - /// \param[out] Trajectory of actor at specified time. - /// \return Update time. - // public: std::chrono::steady_clock::duration ActorTrajectoryAt( - // Entity _id, const std::chrono::steady_clock::duration &_time, - // common::TrajectoryInfo &_traj) const; - - - public: AnimInfo ActorTrajectoryAt( - Entity _id, const std::chrono::steady_clock::duration &_time) const; - + /// \brief Get a skeleon given an id + /// \param[in] _id Actor entity's unique id + /// \return Pointer to requested entity's skeleton + public: common::SkeletonPtr ActorSkeletonById(Entity _id) const; /// \brief Get the animation of actor mesh given an id + /// Use this function if you are animating the actor manually by its + /// skeleton node pose. /// \param[in] _id Entity's unique id - /// \param[in] _time Timepoint for the animation + /// \param[in] _time Simulation time /// \return Map from the skeleton node name to transforms public: std::map ActorMeshAnimationAt( Entity _id, std::chrono::steady_clock::duration _time) const; - public: AnimInfo ActorAnimationAt( + /// \brief Get the skeleton local transforms of actor mesh given an id. + /// Use this function if you are animating the actor manually by its + /// skeleton node pose. + /// \param[in] _id Entity's unique id + /// \param[in] _time SimulationTime + /// \return Map from the skeleton node name to transforms + public: std::map ActorSkeletonTransformsAt( + Entity _id, std::chrono::steady_clock::duration _time) const; + + /// \brief Get the actor animation update data given an id. + /// Use this function to let the render engine handle the actor animation. + /// by setting the animation name to be played. + /// \param[in] _id Entity's unique id + /// \param[in] _time SimulationTime + /// \return Data needed to update the animation, including the name and + /// time of animation to play, and trajectory animation info. + public: AnimationUpdateData ActorAnimationAt( Entity _id, std::chrono::steady_clock::duration _time) const; /// \brief Remove an entity by id diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 034b204294..1f99ff79c3 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -29,6 +29,7 @@ #include #include +#include #include #include @@ -164,8 +165,8 @@ class ignition::gazebo::RenderUtilPrivate actorTransforms; /// \brief A map of entity ids and actor animation info. - public: std::map - actorAnimationInfo; + public: std::map + actorAnimationData; public: std::string prevAnimName; /// \brief True to update skeletons manually using bone poses @@ -257,7 +258,7 @@ void RenderUtil::Update() auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); auto actorTransforms = std::move(this->dataPtr->actorTransforms); - auto actorAnimationInfo= std::move(this->dataPtr->actorAnimationInfo); + auto actorAnimationData = std::move(this->dataPtr->actorAnimationData); this->dataPtr->newScenes.clear(); this->dataPtr->newModels.clear(); @@ -268,7 +269,7 @@ void RenderUtil::Update() this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); this->dataPtr->actorTransforms.clear(); - this->dataPtr->actorAnimationInfo.clear(); + this->dataPtr->actorAnimationData.clear(); this->dataPtr->markerManager.Update(); @@ -431,41 +432,70 @@ void RenderUtil::Update() } else { - for (auto &it : actorAnimationInfo) + for (auto &it : actorAnimationData) { auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(it.first); auto actorVisual = this->dataPtr->sceneManager.NodeById(it.first); if (!actorMesh || !actorVisual) continue; - // actorMesh->UpdateSkeletonAnimation(it.second); - AnimInfo &info = it.second; - if (!info.valid) + + AnimationUpdateData &animData = it.second; + if (!animData.valid) { - ignerr << "invalid animation info" << std::endl; + ignerr << "invalid animation update data" << std::endl; continue; } - // if (!actorMesh->SkeletonAnimationEnabled(info.name)) - // { - // // disable previous anim - // if (!this->dataPtr->prevAnimName.empty()) - // { - // actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->prevAnimName, - // false, false, 0.0); - // } - // // disable previous anim - // // actorMesh->SetSkeletonAnimationEnabled(info.name, true, info.loop); - // actorMesh->SetSkeletonAnimationEnabled(info.name, true, info.loop); - // this->dataPtr->prevAnimName = info.name; - // } - // actorMesh->UpdateSkeletonAnimation(info.time); - - double timeSeconds = std::chrono::duration(info.time).count(); - std::cerr << "info: " << info.name << " " << timeSeconds << std::endl; + // Enable skeleon animation + if (!actorMesh->SkeletonAnimationEnabled(animData.animationName)) + { + // disable previous animation + if (!this->dataPtr->prevAnimName.empty()) + { + actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->prevAnimName, + false, false, 0.0); + } + // enable requested animation + actorMesh->SetSkeletonAnimationEnabled( + animData.animationName, true, animData.loop); + + // Set skeleton root node weight to zero so it is not affected by + // the animation being played. This is needed if trajectory animation + // is enabled. We need to let the trajectory animation set the + // position of the actor instead + common::SkeletonPtr skeleton = + this->dataPtr->sceneManager.ActorSkeletonById(it.first); + if (skeleton) + { + float rootBoneWeight = (animData.followTrajectory) ? 0.0 : 1.0; + std::map weights; + weights[skeleton->RootNode()->Name()] = rootBoneWeight; + actorMesh->SetSkeletonWeights(weights); + } - common::PoseKeyFrame poseFrame(0.0); - if (info.followTrajectory) - info.trajectory.Waypoints()->InterpolatedKeyFrame(poseFrame); + this->dataPtr->prevAnimName = animData.animationName; + } + // update skeleton animation by setting animation time. + // Note that animation time is different from sim time. An actor can + // have multiple animations. Animation time is associated with + // current animation that is being played. should be played. It is also + // adjusted if interpotate_x is enabled + actorMesh->UpdateSkeletonAnimation(animData.time); + + // manually update root transform in order to sync with trajectory + // animation + if (animData.followTrajectory) + { + common::SkeletonPtr skeleton = + this->dataPtr->sceneManager.ActorSkeletonById(it.first); + std::map rootTf; + rootTf[skeleton->RootNode()->Name()] = animData.rootTransform; + actorMesh->SetSkeletonLocalTransforms(rootTf); + } + // update actor trajectory animation + common::PoseKeyFrame poseFrame(0.0); + if (animData.followTrajectory) + animData.trajectory.Waypoints()->InterpolatedKeyFrame(poseFrame); math::Pose3d actorPose; actorPose.Pos() = poseFrame.Translation(); actorPose.Rot() = poseFrame.Rotation(); @@ -851,12 +881,13 @@ void RenderUtilPrivate::UpdateRenderingEntities( if (this->actorManualSkeletonUpdate) { this->actorTransforms[_entity] = - this->sceneManager.ActorMeshAnimationAt(_entity, this->simTime); + this->sceneManager.ActorSkeletonTransformsAt( + _entity, this->simTime); } else { - this->actorAnimationInfo[_entity] = - this->sceneManager.ActorAnimationAt(_entity, this->simTime); + this->actorAnimationData[_entity] = + this->sceneManager.ActorAnimationAt(_entity, this->simTime); } return true; }); diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index d3e067b091..ffae67aeff 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -76,6 +76,12 @@ class ignition::gazebo::SceneManagerPrivate /// \brief Map of sensor entity in Gazebo to sensor pointers. public: std::map sensors; + + /// \brief Helper function to compute actor trajectory at specified tiime + /// \param[in] _id Actor entity's unique id + /// \param[in] _time Simulation time + public: AnimationUpdateData ActorTrajectoryAt( + Entity _id, const std::chrono::steady_clock::duration &_time) const; }; @@ -526,25 +532,18 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, return rendering::VisualPtr(); } - rendering::MeshPtr actorMesh = this->dataPtr->scene->CreateMesh(descriptor); - if (nullptr == actorMesh) - { - ignerr << "Actor skin file [" << descriptor.meshName << "] not found." - << std::endl; - return rendering::VisualPtr(); - } +// rendering::MeshPtr actorMesh = this->dataPtr->scene->CreateMesh(descriptor); +// if (nullptr == actorMesh) +// { +// ignerr << "Actor skin file [" << descriptor.meshName << "] not found." +// << std::endl; +// return rendering::VisualPtr(); +// } unsigned int numAnims = 0; std::map mapAnimNameId; mapAnimNameId[descriptor.meshName] = numAnims++; - rendering::VisualPtr actorVisual = this->dataPtr->scene->CreateVisual(name); - actorVisual->SetLocalPose(_actor.RawPose()); - actorVisual->AddGeometry(actorMesh); - - this->dataPtr->visuals[_id] = actorVisual; - this->dataPtr->actors[_id] = actorMesh; - // Load all animations for (unsigned i = 0; i < _actor.AnimationCount(); ++i) { @@ -583,13 +582,18 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, << "]" << std::endl; return nullptr; } + // collada loader loads animations with name that defaults to + // "animation0", "animation"1", etc causing conflicts in names + // when multiple animations are added to meshSkel. + // So make sure to give it a unique name + firstAnim->SetName(animName); + meshSkel->AddAnimation(firstAnim); mapAnimNameId[animName] = numAnims++; } } this->dataPtr->actorSkeletons[_id] = meshSkel; - std::vector trajectories; if (_actor.TrajectoryCount() != 0) { @@ -668,6 +672,24 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, this->dataPtr->actorTrajectories[_id] = trajectories; + // create mesh with animations + rendering::MeshPtr actorMesh = this->dataPtr->scene->CreateMesh( + descriptor); + if (nullptr == actorMesh) + { + ignerr << "Actor skin file [" << descriptor.meshName << "] not found." + << std::endl; + return rendering::VisualPtr(); + } + + rendering::VisualPtr actorVisual = this->dataPtr->scene->CreateVisual(name); + actorVisual->SetLocalPose(_actor.RawPose()); + actorVisual->AddGeometry(actorMesh); + + this->dataPtr->visuals[_id] = actorVisual; + this->dataPtr->actors[_id] = actorMesh; + + if (parent) parent->AddChild(actorVisual); else @@ -851,114 +873,86 @@ rendering::MeshPtr SceneManager::ActorMeshById(Entity _id) const // } ///////////////////////////////////////////////// -// std::chrono::steady_clock::duration SceneManager::ActorTrajectoryAt( -AnimInfo SceneManager::ActorTrajectoryAt( - Entity _id, - const std::chrono::steady_clock::duration &_time) const +common::SkeletonPtr SceneManager::ActorSkeletonById(Entity _id) const { - // _traj.SetId(-1); - // auto trajIt = this->dataPtr->actorTrajectories.find(_id); - // if (trajIt == this->dataPtr->actorTrajectories.end()) - // { - // return _time; - // } - - AnimInfo info; - auto trajIt = this->dataPtr->actorTrajectories.find(_id); - if (trajIt == this->dataPtr->actorTrajectories.end()) - return info; - - auto trajs = trajIt->second; - bool followTraj = true; - if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) - followTraj = false; + auto it = this->dataPtr->actorSkeletons.find(_id); + if (it != this->dataPtr->actorSkeletons.end()) + return it->second; - auto firstTraj = trajs.begin(); - - common::TrajectoryInfo traj = trajs[0]; + return common::SkeletonPtr(); +} -// using TP = std::chrono::steady_clock::time_point; - auto totalTime = trajs.rbegin()->EndTime() - trajs.begin()->StartTime(); +///////////////////////////////////////////////// +AnimationUpdateData SceneManager::ActorAnimationAt( + Entity _id, std::chrono::steady_clock::duration _time) const +{ + AnimationUpdateData animData; + auto trajIt = this->dataPtr->actorTrajectories.find(_id); + if (trajIt == this->dataPtr->actorTrajectories.end()) + return animData; - // delay start - auto time = _time; - if (time < (trajs.begin()->StartTime() - TP(0ms))) - { - time = std::chrono::steady_clock::duration(0); - } - else - { - time -= trajs.begin()->StartTime() - TP(0ms); - } + auto skelIt = this->dataPtr->actorSkeletons.find(_id); + if (skelIt == this->dataPtr->actorSkeletons.end()) + return animData; - bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) - && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); + animData = this->dataPtr->ActorTrajectoryAt(_id, _time); - if (time >= totalTime && noLoop) - { - time = totalTime; - } + auto skel = skelIt->second; + unsigned int animIndex = animData.trajectory.AnimIndex(); + animData.animationName = skel->Animation(animIndex)->Name(); -// auto poseFrame = common::PoseKeyFrame(0.0); - if (!noLoop || time <= totalTime) + std::string rootNodeName = skel->RootNode()->Name(); + if (animData.followTrajectory) { - while (time > totalTime) + double distance = animData.trajectory.DistanceSoFar(animData.time); + math::Matrix4d rawFrame; + if (distance < 0.1) { - time = time - totalTime; + double timeSeconds = std::chrono::duration(animData.time).count(); + rawFrame = skel->Animation(animIndex)->NodePoseAt( + rootNodeName, timeSeconds, animData.loop); } - if (followTraj) + else { - for (auto &trajectory : trajs) - { - if (trajectory.StartTime() - firstTraj->StartTime() <= time - && trajectory.EndTime() - firstTraj->StartTime() >= time) - { - traj = trajectory; - time -= traj.StartTime() - firstTraj->StartTime(); - - traj.Waypoints()->Time(std::chrono::duration(time).count()); - break; - } - } + common::NodeAnimation *rootNode = + skel->Animation(animIndex)->NodeAnimationByName(rootNodeName); + math::Matrix4d lastPos = rootNode->KeyFrame( + rootNode->FrameCount() - 1).second; + math::Matrix4d firstPos = rootNode->KeyFrame(0).second; + double x = distance; + if (x < firstPos.Translation().X()) + x = firstPos.Translation().X(); + double lastX = lastPos.Translation().X(); + if (x > lastX && !animData.loop) + x = lastX; + while (x > lastX) + x -= lastX; + double time = rootNode->TimeAtX(x); + rawFrame = rootNode->FrameAt(time, animData.loop); + animData.time = std::chrono::duration_cast< + std::chrono::steady_clock::duration>( + std::chrono::duration(time)); } + std::string skinName = skel->NodeNameAnimToSkin(animIndex, rootNodeName); + math::Matrix4d skinTf = skel->AlignTranslation(animIndex, rootNodeName) + * rawFrame * skel->AlignRotation(animIndex, rootNodeName); + + skinTf.SetTranslation(math::Vector3d::Zero); + animData.rootTransform = skinTf; } - // return time; - info.time = time; - info.loop = !noLoop; - info.followTrajectory = followTraj; - info.trajectory = traj; - info.valid = true; - return info; + return animData; } ///////////////////////////////////////////////// -AnimInfo SceneManager::ActorAnimationAt( +std::map SceneManager::ActorMeshAnimationAt( Entity _id, std::chrono::steady_clock::duration _time) const { - AnimInfo animInfo; - auto trajIt = this->dataPtr->actorTrajectories.find(_id); - if (trajIt == this->dataPtr->actorTrajectories.end()) - return animInfo; - - auto skelIt = this->dataPtr->actorSkeletons.find(_id); - if (skelIt == this->dataPtr->actorSkeletons.end()) - return animInfo; - - animInfo = this->ActorTrajectoryAt(_id, _time); - // bool followTraj = animInfo.followTrajectory; - // bool noLoop = animInfo.loop; - // common::TrajectoryInfo traj = animInfo.trajectory; - // auto time = animInfo.time; - - auto skel = skelIt->second; - unsigned int animIndex = animInfo.trajectory.AnimIndex(); - animInfo.name = skel->Animation(animIndex)->Name(); - return animInfo; + return this->ActorSkeletonTransformsAt(_id, _time); } ///////////////////////////////////////////////// -std::map SceneManager::ActorMeshAnimationAt( +std::map SceneManager::ActorSkeletonTransformsAt( Entity _id, std::chrono::steady_clock::duration _time) const { std::map allFrames; @@ -970,25 +964,11 @@ std::map SceneManager::ActorMeshAnimationAt( } // get the trajectory at input time - // The time returned is the time at which the animation should be played - // common::TrajectoryInfo traj; - // auto time = this->ActorTrajectoryAt(_id, _time, traj); - AnimInfo animInfo = this->ActorTrajectoryAt(_id, _time); - bool followTraj = animInfo.followTrajectory; - bool noLoop = animInfo.loop; - common::TrajectoryInfo traj = animInfo.trajectory; - auto time = animInfo.time; - - // auto trajs = trajIt->second; - // bool followTraj = true; - // if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) - // { - // followTraj = false; - // } - - // bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) - // && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); - + AnimationUpdateData animData = this->dataPtr->ActorTrajectoryAt(_id, _time); + bool followTraj = animData.followTrajectory; + bool noLoop = animData.loop; + common::TrajectoryInfo traj = animData.trajectory; + auto time = animData.time; common::PoseKeyFrame poseFrame(0.0); if (followTraj) @@ -1105,3 +1085,73 @@ rendering::VisualPtr SceneManager::TopLevelVisual( return visual; } + +///////////////////////////////////////////////// +AnimationUpdateData SceneManagerPrivate::ActorTrajectoryAt( + Entity _id, + const std::chrono::steady_clock::duration &_time) const +{ + AnimationUpdateData animData; + auto trajIt = this->actorTrajectories.find(_id); + if (trajIt == this->actorTrajectories.end()) + return animData; + + auto trajs = trajIt->second; + bool followTraj = true; + if (1 == trajs.size() && nullptr == trajs[0].Waypoints()) + followTraj = false; + + auto firstTraj = trajs.begin(); + common::TrajectoryInfo traj = trajs[0]; + auto totalTime = trajs.rbegin()->EndTime() - trajs.begin()->StartTime(); + + // delay start + auto time = _time; + if (time < (trajs.begin()->StartTime() - TP(0ms))) + { + time = std::chrono::steady_clock::duration(0); + } + else + { + time -= trajs.begin()->StartTime() - TP(0ms); + } + + bool noLoop = trajs.rbegin()->StartTime() != TP(0ms) + && trajs.rbegin()->StartTime() == trajs.rbegin()->EndTime(); + + if (time >= totalTime && noLoop) + { + time = totalTime; + } + + if (!noLoop || time <= totalTime) + { + while (time > totalTime) + { + time = time - totalTime; + } + if (followTraj) + { + for (auto &trajectory : trajs) + { + if (trajectory.StartTime() - firstTraj->StartTime() <= time + && trajectory.EndTime() - firstTraj->StartTime() >= time) + { + traj = trajectory; + time -= traj.StartTime() - firstTraj->StartTime(); + + traj.Waypoints()->Time(std::chrono::duration(time).count()); + break; + } + } + } + } + + // return time; + animData.time = time; + animData.loop = !noLoop; + animData.followTrajectory = followTraj; + animData.trajectory = traj; + animData.valid = true; + return animData; +} From 4521cf80984be21ae04fe2c85a3e2dc78c1d2f2f Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 27 Mar 2020 15:21:47 -0700 Subject: [PATCH 05/19] cleanup --- src/rendering/RenderUtil.cc | 14 ++++++++------ src/rendering/SceneManager.cc | 32 ++++++++++++++++---------------- 2 files changed, 24 insertions(+), 22 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 1f99ff79c3..dc5ff9d472 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -167,7 +167,9 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of entity ids and actor animation info. public: std::map actorAnimationData; - public: std::string prevAnimName; + + /// \brief Name of skeleton animation that is currently playing + public: std::string skelAnimName; /// \brief True to update skeletons manually using bone poses /// (see actorTransforms). False to let render engine update animation @@ -445,13 +447,13 @@ void RenderUtil::Update() ignerr << "invalid animation update data" << std::endl; continue; } - // Enable skeleon animation + // Enable skeleton animation if (!actorMesh->SkeletonAnimationEnabled(animData.animationName)) { - // disable previous animation - if (!this->dataPtr->prevAnimName.empty()) + // disable current animation + if (!this->dataPtr->skelAnimName.empty()) { - actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->prevAnimName, + actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->skelAnimName, false, false, 0.0); } // enable requested animation @@ -472,7 +474,7 @@ void RenderUtil::Update() actorMesh->SetSkeletonWeights(weights); } - this->dataPtr->prevAnimName = animData.animationName; + this->dataPtr->skelAnimName= animData.animationName; } // update skeleton animation by setting animation time. // Note that animation time is different from sim time. An actor can diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index ffae67aeff..0057f96ec2 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -80,6 +80,8 @@ class ignition::gazebo::SceneManagerPrivate /// \brief Helper function to compute actor trajectory at specified tiime /// \param[in] _id Actor entity's unique id /// \param[in] _time Simulation time + /// \return AnimationUpdateData with trajectory related fields filled. It + /// also sets the time point in which the animation should be played public: AnimationUpdateData ActorTrajectoryAt( Entity _id, const std::chrono::steady_clock::duration &_time) const; }; @@ -532,14 +534,6 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, return rendering::VisualPtr(); } -// rendering::MeshPtr actorMesh = this->dataPtr->scene->CreateMesh(descriptor); -// if (nullptr == actorMesh) -// { -// ignerr << "Actor skin file [" << descriptor.meshName << "] not found." -// << std::endl; -// return rendering::VisualPtr(); -// } - unsigned int numAnims = 0; std::map mapAnimNameId; mapAnimNameId[descriptor.meshName] = numAnims++; @@ -864,14 +858,6 @@ rendering::MeshPtr SceneManager::ActorMeshById(Entity _id) const return rendering::MeshPtr(); } -///////////////////////////////////////////////// -// bool SceneManager::CorrectTime( -// const std::vector &_trajs, -// std::chrono::steady_clock::duration &_time) const -// { -// -// } - ///////////////////////////////////////////////// common::SkeletonPtr SceneManager::ActorSkeletonById(Entity _id) const { @@ -914,6 +900,11 @@ AnimationUpdateData SceneManager::ActorAnimationAt( } else { + // logic here is mostly taken from + // common::SkeletonAnimation::PoseAtX + // We should consider refactoring part of that function to return + // PoseAtX for only one skeleton node in addition to the current + // function that computes PoseAtX for all skeleton nodes common::NodeAnimation *rootNode = skel->Animation(animIndex)->NodeAnimationByName(rootNodeName); math::Matrix4d lastPos = rootNode->KeyFrame( @@ -927,7 +918,14 @@ AnimationUpdateData SceneManager::ActorAnimationAt( x = lastX; while (x > lastX) x -= lastX; + + // update animation timepoint for root node + // this should be the time that is used in the + // SkeletonAnimationEnabled call double time = rootNode->TimeAtX(x); + + // get raw skeleton transform for root node. Needed to keep skeleton + // animation in sync with trajectory animation rawFrame = rootNode->FrameAt(time, animData.loop); animData.time = std::chrono::duration_cast< std::chrono::steady_clock::duration>( @@ -937,6 +935,8 @@ AnimationUpdateData SceneManager::ActorAnimationAt( math::Matrix4d skinTf = skel->AlignTranslation(animIndex, rootNodeName) * rawFrame * skel->AlignRotation(animIndex, rootNodeName); + // zero out translation since we only need rotation to sync with actor + // trajectory animation skinTf.SetTranslation(math::Vector3d::Zero); animData.rootTransform = skinTf; } From 14cf62eb612fddb20ae77cfddd7a34537e479de1 Mon Sep 17 00:00:00 2001 From: chapulina Date: Fri, 27 Mar 2020 17:48:59 -0700 Subject: [PATCH 06/19] unordered map, typo --- examples/plugin/command_actor/CommandActor.hh | 2 +- src/rendering/RenderUtil.cc | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/plugin/command_actor/CommandActor.hh b/examples/plugin/command_actor/CommandActor.hh index 124a9914df..feeab87f16 100644 --- a/examples/plugin/command_actor/CommandActor.hh +++ b/examples/plugin/command_actor/CommandActor.hh @@ -53,7 +53,7 @@ namespace command_actor /// set. private: std::map origins; - /// \brief Trajecotry poses to change, where the key is the number of + /// \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 trajPoses; diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index a04f4d3171..17d652da41 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -15,7 +15,7 @@ * */ -#include +#include #include #include @@ -154,17 +154,17 @@ class ignition::gazebo::RenderUtilPrivate /// \brief Map of ids of entites to be removed and sim iteration when the /// remove request is received - public: std::map removeEntities; + public: std::unordered_map removeEntities; - /// \brief A map of entity ids and pose updates. - public: std::map entityPoses; + /// \brief A unordered_map of entity ids and pose updates. + public: std::unordered_map entityPoses; /// \brief A map of entity ids and actor transforms. public: std::map> actorTransforms; /// \brief A map of entity ids and trajectory pose updates. - public: std::map trajectoryPoses; + public: std::unordered_map trajectoryPoses; /// \brief Mutex to protect updates public: std::mutex updateMutex; From 22719777b69506c6df31372379563bf0bb090b7c Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 27 Mar 2020 19:28:59 -0700 Subject: [PATCH 07/19] minor update --- src/rendering/RenderUtil.cc | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index dc5ff9d472..968901d291 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -165,8 +165,7 @@ class ignition::gazebo::RenderUtilPrivate actorTransforms; /// \brief A map of entity ids and actor animation info. - public: std::map - actorAnimationData; + public: std::map actorAnimationData; /// \brief Name of skeleton animation that is currently playing public: std::string skelAnimName; From d6bcb2648242bfe5bca7976f1a12d5cc55bdc02c Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 27 Mar 2020 21:11:41 -0700 Subject: [PATCH 08/19] code check --- include/ignition/gazebo/components/Pose.hh | 3 ++- src/rendering/RenderUtil.cc | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/include/ignition/gazebo/components/Pose.hh b/include/ignition/gazebo/components/Pose.hh index b07faff7da..8d67c51d3c 100644 --- a/include/ignition/gazebo/components/Pose.hh +++ b/include/ignition/gazebo/components/Pose.hh @@ -43,7 +43,8 @@ namespace components /// \brief A component type that contains pose, ignition::math::Pose3d, /// information within a trajectory. - using TrajectoryPose = Component; + using TrajectoryPose = + Component; IGN_GAZEBO_REGISTER_COMPONENT( "ign_gazebo_components.TrajectoryPose", TrajectoryPose) } diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 2b33e3f0fd..4b8493c9e6 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -494,7 +494,7 @@ void RenderUtil::Update() actorMesh->SetSkeletonWeights(weights); } - this->dataPtr->skelAnimName= animData.animationName; + this->dataPtr->skelAnimName = animData.animationName; } // update skeleton animation by setting animation time. // Note that animation time is different from sim time. An actor can From 55699cf92e4982ddeec0d8e6a5b2c95db88190f7 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 27 Mar 2020 21:39:11 -0700 Subject: [PATCH 09/19] changelog --- Changelog.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Changelog.md b/Changelog.md index 85dbdf849f..c89caeff06 100644 --- a/Changelog.md +++ b/Changelog.md @@ -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. Support and * [Pull Request 542](https://bitbucket.org/ignitionrobotics/ign-gazebo/pull-requests/542) From b158ae2fef4ecb7315a637654dc9ba7a7a2168e3 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 2 Apr 2020 11:00:21 -0700 Subject: [PATCH 10/19] use unordered map --- src/rendering/RenderUtil.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index b17b94a79b..dc597bb056 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -511,7 +511,7 @@ void RenderUtil::Update() if (skeleton) { float rootBoneWeight = (animData.followTrajectory) ? 0.0 : 1.0; - std::map weights; + std::unordered_map weights; weights[skeleton->RootNode()->Name()] = rootBoneWeight; actorMesh->SetSkeletonWeights(weights); } @@ -521,8 +521,8 @@ void RenderUtil::Update() // update skeleton animation by setting animation time. // Note that animation time is different from sim time. An actor can // have multiple animations. Animation time is associated with - // current animation that is being played. should be played. It is also - // adjusted if interpotate_x is enabled + // current animation that is being played. It is also adjusted if + // interpotate_x is enabled actorMesh->UpdateSkeletonAnimation(animData.time); // manually update root transform in order to sync with trajectory From 87b2bef6f45d78d5f1c715a2609950a9a0dcfa12 Mon Sep 17 00:00:00 2001 From: chapulina Date: Fri, 3 Apr 2020 15:37:50 -0700 Subject: [PATCH 11/19] typos --- include/ignition/gazebo/rendering/SceneManager.hh | 10 +++++----- src/rendering/RenderUtil.cc | 7 ++++--- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 456f08072b..6df7cd39e8 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -48,20 +48,20 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { // Forward declaration class SceneManagerPrivate; - /// \brief Data structure for updaing skeleton animations + /// \brief Data structure for updating skeleton animations class AnimationUpdateData { /// \brief Timepoint in the animation. /// Note that animation time is different from sim time. An actor can /// have multiple animations. Animation time is associated with /// current animation that is being played. This value is also adjusted if - /// interpotate_x is enabled + /// interpolate_x is enabled public: std::chrono::steady_clock::duration time; /// \brief True if animation is looped public: bool loop = false; - /// \brief True trajectory animation is on + /// \brief True if trajectory animation is on public: bool followTrajectory = false; /// \brief Trajectory to be followed @@ -72,7 +72,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: std::string animationName; /// \brief Transform of the root node in the skeleton. The actor's - /// skeleton's root node transform need to be set if trajectory + /// skeleton's root node transform needs to be set if trajectory /// animation is enabled. This field is set only if the actor /// is not animated by manually using skeleton transforms public: math::Matrix4d rootTransform; @@ -168,7 +168,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \return Pointer to requested entity's mesh public: rendering::MeshPtr ActorMeshById(Entity _id) const; - /// \brief Get a skeleon given an id + /// \brief Get a skeleton given an id /// \param[in] _id Actor entity's unique id /// \return Pointer to requested entity's skeleton public: common::SkeletonPtr ActorSkeletonById(Entity _id) const; diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index dc597bb056..36bf5b32ad 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -179,6 +179,7 @@ class ignition::gazebo::RenderUtilPrivate /// \brief True to update skeletons manually using bone poses /// (see actorTransforms). False to let render engine update animation /// based on sim time. + /// \todo(anyone) Let this be turned on from a component public: bool actorManualSkeletonUpdate = false; /// \brief Mutex to protect updates @@ -518,11 +519,11 @@ void RenderUtil::Update() this->dataPtr->skelAnimName = animData.animationName; } - // update skeleton animation by setting animation time. + // Update skeleton animation by setting animation time. // Note that animation time is different from sim time. An actor can // have multiple animations. Animation time is associated with - // current animation that is being played. It is also adjusted if - // interpotate_x is enabled + // current animation that is being played. It is also adjusted if + // interpotate_x is enabled. actorMesh->UpdateSkeletonAnimation(animData.time); // manually update root transform in order to sync with trajectory From 9751393a18d6b66618465af9cbbe20cc80d831f7 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 3 Apr 2020 17:28:07 -0700 Subject: [PATCH 12/19] address feedback --- include/ignition/gazebo/rendering/SceneManager.hh | 3 ++- src/rendering/RenderUtil.cc | 8 ++++++++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 6df7cd39e8..e6727f078d 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -179,6 +179,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \param[in] _id Entity's unique id /// \param[in] _time Simulation time /// \return Map from the skeleton node name to transforms + /// \deprecated see ActorSkeletonTransformAt public: std::map IGN_DEPRECATED(4.0) ActorMeshAnimationAt( Entity _id, std::chrono::steady_clock::duration _time) const; @@ -196,7 +197,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// Use this function to let the render engine handle the actor animation. /// by setting the animation name to be played. /// \param[in] _id Entity's unique id - /// \param[in] _time SimulationTime + /// \param[in] _time Simulation time /// \return Data needed to update the animation, including the name and /// time of animation to play, and trajectory animation info. public: AnimationUpdateData ActorAnimationAt( diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 36bf5b32ad..4c29bf347d 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -448,7 +448,11 @@ void RenderUtil::Update() auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(tf.first); auto actorVisual = this->dataPtr->sceneManager.NodeById(tf.first); if (!actorMesh || !actorVisual) + { + ignerr << "Actor with Entity ID '" << tf.first << "'. not found. " + << "Skipping skeleton animation update." << std::endl; continue; + } math::Pose3d globalPose; if (entityPoses.find(tf.first) != entityPoses.end()) @@ -482,7 +486,11 @@ void RenderUtil::Update() auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(it.first); auto actorVisual = this->dataPtr->sceneManager.NodeById(it.first); if (!actorMesh || !actorVisual) + { + ignerr << "Actor with Entity ID '" << it.first << "'. not found. " + << "Skipping skeleton animation update." << std::endl; continue; + } AnimationUpdateData &animData = it.second; if (!animData.valid) From 47f8ff6031b3a2634ae2e9d9a2d4575dba5c82a1 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 3 Apr 2020 17:50:27 -0700 Subject: [PATCH 13/19] fix disabling skel anim --- src/rendering/RenderUtil.cc | 19 +++++++++---------- src/rendering/SceneManager.cc | 1 + 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 4c29bf347d..063240618f 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -173,9 +174,6 @@ class ignition::gazebo::RenderUtilPrivate /// \brief A map of entity ids and actor animation info. public: std::unordered_map actorAnimationData; - /// \brief Name of skeleton animation that is currently playing - public: std::string skelAnimName; - /// \brief True to update skeletons manually using bone poses /// (see actorTransforms). False to let render engine update animation /// based on sim time. @@ -485,7 +483,9 @@ void RenderUtil::Update() { auto actorMesh = this->dataPtr->sceneManager.ActorMeshById(it.first); auto actorVisual = this->dataPtr->sceneManager.NodeById(it.first); - if (!actorMesh || !actorVisual) + auto actorSkel = this->dataPtr->sceneManager.ActorSkeletonById( + it.first); + if (!actorMesh || !actorVisual || !actorSkel) { ignerr << "Actor with Entity ID '" << it.first << "'. not found. " << "Skipping skeleton animation update." << std::endl; @@ -501,12 +501,13 @@ void RenderUtil::Update() // Enable skeleton animation if (!actorMesh->SkeletonAnimationEnabled(animData.animationName)) { - // disable current animation - if (!this->dataPtr->skelAnimName.empty()) + // disable all animations for this actor + for (unsigned int i = 0; i < actorSkel->AnimationCount(); ++i) { - actorMesh->SetSkeletonAnimationEnabled(this->dataPtr->skelAnimName, - false, false, 0.0); + actorMesh->SetSkeletonAnimationEnabled( + actorSkel->Animation(i)->Name(), false, false, 0.0); } + // enable requested animation actorMesh->SetSkeletonAnimationEnabled( animData.animationName, true, animData.loop); @@ -524,8 +525,6 @@ void RenderUtil::Update() weights[skeleton->RootNode()->Name()] = rootBoneWeight; actorMesh->SetSkeletonWeights(weights); } - - this->dataPtr->skelAnimName = animData.animationName; } // Update skeleton animation by setting animation time. // Note that animation time is different from sim time. An actor can diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index d8d91e2616..b2d212d43f 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -551,6 +551,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, std::string animFilename = asFullPath( _actor.AnimationByIndex(i)->Filename(), _actor.AnimationByIndex(i)->FilePath()); + double animScale = _actor.AnimationByIndex(i)->Scale(); std::string extension = animFilename.substr(animFilename.rfind('.') + 1, From f003c3dda69b67f2446bee787ec7165ffa5e5b77 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 10 Apr 2020 16:13:36 -0700 Subject: [PATCH 14/19] add actor crowd world, and fix adding duplicate animations --- examples/worlds/actor_crowd.sdf | 3887 +++++++++++++++++++++++++++++++ src/rendering/RenderUtil.cc | 26 +- src/rendering/SceneManager.cc | 51 +- 3 files changed, 3941 insertions(+), 23 deletions(-) create mode 100644 examples/worlds/actor_crowd.sdf diff --git a/examples/worlds/actor_crowd.sdf b/examples/worlds/actor_crowd.sdf new file mode 100644 index 0000000000..55fdf62c78 --- /dev/null +++ b/examples/worlds/actor_crowd.sdf @@ -0,0 +1,3887 @@ + + + + + + + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + World control + false + false + 72 + 121 + 1 + + floating + + + + + + + true + true + true + /world/actors/control + /world/actors/stats + + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + /world/actors/stats + + + + + + + false + docked + + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0.0 0.0 1 + + + + + + + 0.0 0.0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + demo_actor_0_0 + -12 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_1 + -12 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_2 + -12 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_3 + -12 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_4 + -12 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_5 + -12 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_6 + -12 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_7 + -12 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_8 + -12 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_9 + -12 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_10 + -12 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_11 + -12 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_12 + -12 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_13 + -12 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_14 + -12 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_15 + -12 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_16 + -12 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_17 + -12 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_18 + -12 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_19 + -12 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_20 + -12 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_21 + -12 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_22 + -12 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_23 + -12 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_0_24 + -12 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_1_0 + -11 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_1 + -11 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_2 + -11 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_3 + -11 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_4 + -11 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_5 + -11 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_6 + -11 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_7 + -11 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_8 + -11 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_9 + -11 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_10 + -11 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_11 + -11 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_12 + -11 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_13 + -11 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_14 + -11 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_15 + -11 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_16 + -11 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_17 + -11 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_18 + -11 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_19 + -11 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_20 + -11 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_21 + -11 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_22 + -11 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_23 + -11 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_1_24 + -11 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_2_0 + -10 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_1 + -10 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_2 + -10 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_3 + -10 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_4 + -10 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_5 + -10 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_6 + -10 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_7 + -10 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_8 + -10 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_9 + -10 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_10 + -10 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_11 + -10 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_12 + -10 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_13 + -10 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_14 + -10 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_15 + -10 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_16 + -10 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_17 + -10 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_18 + -10 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_19 + -10 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_20 + -10 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_21 + -10 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_22 + -10 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_23 + -10 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_2_24 + -10 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_3_0 + -9 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_1 + -9 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_2 + -9 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_3 + -9 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_4 + -9 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_5 + -9 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_6 + -9 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_7 + -9 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_8 + -9 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_9 + -9 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_10 + -9 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_11 + -9 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_12 + -9 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_13 + -9 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_14 + -9 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_15 + -9 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_16 + -9 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_17 + -9 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_18 + -9 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_19 + -9 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_20 + -9 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_21 + -9 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_22 + -9 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_23 + -9 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_3_24 + -9 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_4_0 + -8 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_1 + -8 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_2 + -8 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_3 + -8 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_4 + -8 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_5 + -8 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_6 + -8 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_7 + -8 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_8 + -8 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_9 + -8 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_10 + -8 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_11 + -8 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_12 + -8 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_13 + -8 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_14 + -8 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_15 + -8 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_16 + -8 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_17 + -8 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_18 + -8 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_19 + -8 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_20 + -8 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_21 + -8 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_22 + -8 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_23 + -8 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_4_24 + -8 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_5_0 + -7 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_1 + -7 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_2 + -7 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_3 + -7 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_4 + -7 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_5 + -7 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_6 + -7 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_7 + -7 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_8 + -7 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_9 + -7 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_10 + -7 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_11 + -7 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_12 + -7 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_13 + -7 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_14 + -7 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_15 + -7 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_16 + -7 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_17 + -7 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_18 + -7 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_19 + -7 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_20 + -7 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_21 + -7 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_22 + -7 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_23 + -7 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_5_24 + -7 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_6_0 + -6 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_1 + -6 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_2 + -6 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_3 + -6 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_4 + -6 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_5 + -6 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_6 + -6 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_7 + -6 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_8 + -6 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_9 + -6 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_10 + -6 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_11 + -6 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_12 + -6 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_13 + -6 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_14 + -6 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_15 + -6 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_16 + -6 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_17 + -6 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_18 + -6 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_19 + -6 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_20 + -6 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_21 + -6 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_22 + -6 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_23 + -6 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_6_24 + -6 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_7_0 + -5 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_1 + -5 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_2 + -5 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_3 + -5 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_4 + -5 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_5 + -5 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_6 + -5 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_7 + -5 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_8 + -5 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_9 + -5 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_10 + -5 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_11 + -5 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_12 + -5 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_13 + -5 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_14 + -5 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_15 + -5 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_16 + -5 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_17 + -5 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_18 + -5 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_19 + -5 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_20 + -5 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_21 + -5 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_22 + -5 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_23 + -5 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_7_24 + -5 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_8_0 + -4 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_1 + -4 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_2 + -4 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_3 + -4 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_4 + -4 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_5 + -4 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_6 + -4 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_7 + -4 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_8 + -4 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_9 + -4 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_10 + -4 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_11 + -4 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_12 + -4 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_13 + -4 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_14 + -4 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_15 + -4 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_16 + -4 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_17 + -4 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_18 + -4 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_19 + -4 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_20 + -4 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_21 + -4 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_22 + -4 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_23 + -4 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_8_24 + -4 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_9_0 + -3 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_1 + -3 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_2 + -3 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_3 + -3 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_4 + -3 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_5 + -3 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_6 + -3 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_7 + -3 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_8 + -3 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_9 + -3 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_10 + -3 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_11 + -3 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_12 + -3 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_13 + -3 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_14 + -3 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_15 + -3 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_16 + -3 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_17 + -3 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_18 + -3 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_19 + -3 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_20 + -3 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_21 + -3 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_22 + -3 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_23 + -3 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_9_24 + -3 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_10_0 + -2 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_1 + -2 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_2 + -2 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_3 + -2 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_4 + -2 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_5 + -2 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_6 + -2 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_7 + -2 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_8 + -2 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_9 + -2 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_10 + -2 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_11 + -2 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_12 + -2 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_13 + -2 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_14 + -2 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_15 + -2 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_16 + -2 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_17 + -2 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_18 + -2 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_19 + -2 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_20 + -2 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_21 + -2 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_22 + -2 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_23 + -2 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_10_24 + -2 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_11_0 + -1 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_1 + -1 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_2 + -1 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_3 + -1 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_4 + -1 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_5 + -1 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_6 + -1 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_7 + -1 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_8 + -1 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_9 + -1 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_10 + -1 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_11 + -1 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_12 + -1 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_13 + -1 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_14 + -1 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_15 + -1 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_16 + -1 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_17 + -1 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_18 + -1 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_19 + -1 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_20 + -1 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_21 + -1 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_22 + -1 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_23 + -1 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_11_24 + -1 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_12_0 + 0 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_1 + 0 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_2 + 0 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_3 + 0 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_4 + 0 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_5 + 0 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_6 + 0 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_7 + 0 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_8 + 0 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_9 + 0 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_10 + 0 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_11 + 0 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_12 + 0 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_13 + 0 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_14 + 0 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_15 + 0 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_16 + 0 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_17 + 0 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_18 + 0 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_19 + 0 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_20 + 0 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_21 + 0 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_22 + 0 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_23 + 0 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_12_24 + 0 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_13_0 + 1 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_1 + 1 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_2 + 1 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_3 + 1 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_4 + 1 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_5 + 1 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_6 + 1 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_7 + 1 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_8 + 1 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_9 + 1 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_10 + 1 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_11 + 1 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_12 + 1 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_13 + 1 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_14 + 1 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_15 + 1 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_16 + 1 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_17 + 1 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_18 + 1 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_19 + 1 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_20 + 1 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_21 + 1 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_22 + 1 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_23 + 1 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_13_24 + 1 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_14_0 + 2 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_1 + 2 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_2 + 2 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_3 + 2 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_4 + 2 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_5 + 2 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_6 + 2 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_7 + 2 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_8 + 2 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_9 + 2 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_10 + 2 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_11 + 2 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_12 + 2 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_13 + 2 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_14 + 2 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_15 + 2 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_16 + 2 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_17 + 2 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_18 + 2 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_19 + 2 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_20 + 2 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_21 + 2 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_22 + 2 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_23 + 2 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_14_24 + 2 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_15_0 + 3 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_1 + 3 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_2 + 3 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_3 + 3 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_4 + 3 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_5 + 3 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_6 + 3 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_7 + 3 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_8 + 3 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_9 + 3 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_10 + 3 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_11 + 3 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_12 + 3 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_13 + 3 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_14 + 3 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_15 + 3 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_16 + 3 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_17 + 3 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_18 + 3 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_19 + 3 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_20 + 3 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_21 + 3 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_22 + 3 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_23 + 3 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_15_24 + 3 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_16_0 + 4 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_1 + 4 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_2 + 4 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_3 + 4 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_4 + 4 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_5 + 4 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_6 + 4 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_7 + 4 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_8 + 4 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_9 + 4 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_10 + 4 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_11 + 4 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_12 + 4 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_13 + 4 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_14 + 4 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_15 + 4 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_16 + 4 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_17 + 4 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_18 + 4 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_19 + 4 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_20 + 4 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_21 + 4 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_22 + 4 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_23 + 4 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_16_24 + 4 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_17_0 + 5 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_1 + 5 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_2 + 5 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_3 + 5 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_4 + 5 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_5 + 5 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_6 + 5 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_7 + 5 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_8 + 5 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_9 + 5 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_10 + 5 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_11 + 5 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_12 + 5 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_13 + 5 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_14 + 5 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_15 + 5 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_16 + 5 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_17 + 5 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_18 + 5 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_19 + 5 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_20 + 5 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_21 + 5 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_22 + 5 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_23 + 5 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_17_24 + 5 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_18_0 + 6 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_1 + 6 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_2 + 6 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_3 + 6 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_4 + 6 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_5 + 6 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_6 + 6 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_7 + 6 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_8 + 6 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_9 + 6 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_10 + 6 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_11 + 6 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_12 + 6 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_13 + 6 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_14 + 6 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_15 + 6 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_16 + 6 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_17 + 6 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_18 + 6 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_19 + 6 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_20 + 6 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_21 + 6 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_22 + 6 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_23 + 6 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_18_24 + 6 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_19_0 + 7 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_1 + 7 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_2 + 7 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_3 + 7 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_4 + 7 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_5 + 7 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_6 + 7 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_7 + 7 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_8 + 7 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_9 + 7 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_10 + 7 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_11 + 7 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_12 + 7 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_13 + 7 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_14 + 7 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_15 + 7 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_16 + 7 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_17 + 7 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_18 + 7 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_19 + 7 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_20 + 7 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_21 + 7 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_22 + 7 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_23 + 7 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_19_24 + 7 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_20_0 + 8 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_1 + 8 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_2 + 8 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_3 + 8 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_4 + 8 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_5 + 8 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_6 + 8 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_7 + 8 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_8 + 8 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_9 + 8 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_10 + 8 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_11 + 8 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_12 + 8 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_13 + 8 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_14 + 8 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_15 + 8 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_16 + 8 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_17 + 8 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_18 + 8 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_19 + 8 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_20 + 8 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_21 + 8 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_22 + 8 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_23 + 8 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_20_24 + 8 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_21_0 + 9 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_1 + 9 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_2 + 9 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_3 + 9 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_4 + 9 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_5 + 9 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_6 + 9 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_7 + 9 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_8 + 9 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_9 + 9 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_10 + 9 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_11 + 9 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_12 + 9 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_13 + 9 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_14 + 9 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_15 + 9 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_16 + 9 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_17 + 9 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_18 + 9 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_19 + 9 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_20 + 9 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_21 + 9 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_22 + 9 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_23 + 9 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_21_24 + 9 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_22_0 + 10 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_1 + 10 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_2 + 10 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_3 + 10 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_4 + 10 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_5 + 10 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_6 + 10 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_7 + 10 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_8 + 10 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_9 + 10 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_10 + 10 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_11 + 10 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_12 + 10 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_13 + 10 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_14 + 10 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_15 + 10 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_16 + 10 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_17 + 10 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_18 + 10 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_19 + 10 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_20 + 10 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_21 + 10 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_22 + 10 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_23 + 10 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_22_24 + 10 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_23_0 + 11 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_1 + 11 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_2 + 11 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_3 + 11 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_4 + 11 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_5 + 11 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_6 + 11 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_7 + 11 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_8 + 11 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_9 + 11 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_10 + 11 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_11 + 11 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_12 + 11 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_13 + 11 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_14 + 11 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_15 + 11 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_16 + 11 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_17 + 11 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_18 + 11 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_19 + 11 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_20 + 11 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_21 + 11 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_22 + 11 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_23 + 11 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_23_24 + 11 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + +w + + demo_actor_24_0 + 12 -12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_1 + 12 -11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_2 + 12 -10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_3 + 12 -9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_4 + 12 -8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_5 + 12 -7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_6 + 12 -6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_7 + 12 -5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_8 + 12 -4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_9 + 12 -3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_10 + 12 -2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_11 + 12 -1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_12 + 12 0 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_13 + 12 1 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_14 + 12 2 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_15 + 12 3 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_16 + 12 4 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_17 + 12 5 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_18 + 12 6 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_19 + 12 7 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_20 + 12 8 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_21 + 12 9 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_22 + 12 10 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_23 + 12 11 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + demo_actor_24_24 + 12 12 0 0 0 0 + https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + + + + diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index b6f990fe90..e112ba8f44 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -310,7 +310,6 @@ void RenderUtil::Update() newSensors = std::move(this->dataPtr->newSensors); this->dataPtr->newSensors.clear(); } - this->dataPtr->updateMutex.unlock(); // scene - only one scene is supported for now @@ -491,6 +490,7 @@ void RenderUtil::Update() tf.second.erase("actorPose"); actorMesh->SetSkeletonLocalTransforms(tf.second); } + } else { @@ -585,21 +585,21 @@ void RenderUtil::Update() actorVisual->SetLocalPose(trajPose + globalPose); } } + } - // set visual temperature - for (auto &temp : entityTemp) - { - auto node = this->dataPtr->sceneManager.NodeById(temp.first); - if (!node) - continue; + // set visual temperature + for (auto &temp : entityTemp) + { + auto node = this->dataPtr->sceneManager.NodeById(temp.first); + if (!node) + continue; - auto visual = - std::dynamic_pointer_cast(node); - if (!visual) - continue; + auto visual = + std::dynamic_pointer_cast(node); + if (!visual) + continue; - visual->SetUserData("temperature", temp.second); - } + visual->SetUserData("temperature", temp.second); } } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index dff9694e15..390879684c 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -536,6 +536,8 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, return rendering::VisualPtr(); } + // todo(anyone) create a copy of meshSkel so we don't modify the original + // when adding animations! common::SkeletonPtr meshSkel = descriptor.mesh->MeshSkeleton(); if (nullptr == meshSkel) { @@ -565,21 +567,38 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, if (extension == "bvh") { - meshSkel->AddBvhAnimation(animFilename, animScale); + // do not add duplicate animation + // start checking from index 1 since index 0 is reserved by skin mesh + bool addAnim = true; + for (unsigned int a = 1; a < meshSkel->AnimationCount(); ++a) + { + if (meshSkel->Animation(a)->Name() == animFilename) + { + addAnim = false; + break; + } + } + if (addAnim) + meshSkel->AddBvhAnimation(animFilename, animScale); mapAnimNameId[animName] = numAnims++; } else if (extension == "dae") { - common::MeshManager::Instance()->Load(animFilename); - auto animMesh = common::MeshManager::Instance()->MeshByName(animFilename); - - // add the first animation - if (animMesh->MeshSkeleton()->AnimationCount() > 1) + // Load the mesh if it has not been loaded before + const common::Mesh *animMesh = nullptr; + if (!meshManager->HasMesh(animFilename)) { - ignwarn << "File [" << animFilename - << "] has more than one animation, but only the 1st one is used." - << std::endl; + animMesh = meshManager->Load(animFilename); + if (animMesh->MeshSkeleton()->AnimationCount() > 1) + { + ignwarn << "File [" << animFilename + << "] has more than one animation, but only the 1st one is used." + << std::endl; + } } + animMesh = meshManager->MeshByName(animFilename); + + // add the first animation auto firstAnim = animMesh->MeshSkeleton()->Animation(0); if (nullptr == firstAnim) { @@ -593,7 +612,19 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, // So make sure to give it a unique name firstAnim->SetName(animName); - meshSkel->AddAnimation(firstAnim); + // do not add duplicate animation + // start checking from index 1 since index 0 is reserved by skin mesh + bool addAnim = true; + for (unsigned int a = 1; a < meshSkel->AnimationCount(); ++a) + { + if (meshSkel->Animation(a)->Name() == animName) + { + addAnim = false; + break; + } + } + if (addAnim) + meshSkel->AddAnimation(firstAnim); mapAnimNameId[animName] = numAnims++; } } From 84a09e49c74bb66de5e5d1327f67982e7ee8c2a9 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 10 Apr 2020 16:14:17 -0700 Subject: [PATCH 15/19] add actor crowd world, and fix adding duplicate animations --- src/rendering/RenderUtil.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index e112ba8f44..b5e2722a1e 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -490,7 +490,6 @@ void RenderUtil::Update() tf.second.erase("actorPose"); actorMesh->SetSkeletonLocalTransforms(tf.second); } - } else { From b492c8eafb63997a86444131d5be0c7bb16b6a24 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 10 Apr 2020 16:22:08 -0700 Subject: [PATCH 16/19] fix sdf --- examples/worlds/actor_crowd.sdf | 52 +++++++++++++++++---------------- 1 file changed, 27 insertions(+), 25 deletions(-) diff --git a/examples/worlds/actor_crowd.sdf b/examples/worlds/actor_crowd.sdf index 55fdf62c78..dcb5c5e834 100644 --- a/examples/worlds/actor_crowd.sdf +++ b/examples/worlds/actor_crowd.sdf @@ -1,6 +1,6 @@ @@ -133,6 +133,7 @@ + demo_actor_0_0 -12 -12 0 0 0 0 @@ -282,7 +283,7 @@ -12 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_1_0 -11 -12 0 0 0 0 @@ -432,7 +433,7 @@ w -11 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_2_0 -10 -12 0 0 0 0 @@ -582,7 +583,7 @@ w -10 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_3_0 -9 -12 0 0 0 0 @@ -732,7 +733,7 @@ w -9 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_4_0 -8 -12 0 0 0 0 @@ -882,7 +883,7 @@ w -8 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_5_0 -7 -12 0 0 0 0 @@ -1032,7 +1033,7 @@ w -7 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_6_0 -6 -12 0 0 0 0 @@ -1182,7 +1183,7 @@ w -6 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_7_0 -5 -12 0 0 0 0 @@ -1332,7 +1333,7 @@ w -5 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_8_0 -4 -12 0 0 0 0 @@ -1482,7 +1483,7 @@ w -4 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_9_0 -3 -12 0 0 0 0 @@ -1632,7 +1633,7 @@ w -3 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_10_0 -2 -12 0 0 0 0 @@ -1782,7 +1783,7 @@ w -2 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_11_0 -1 -12 0 0 0 0 @@ -1932,7 +1933,7 @@ w -1 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_12_0 0 -12 0 0 0 0 @@ -2082,7 +2083,7 @@ w 0 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_13_0 1 -12 0 0 0 0 @@ -2232,7 +2233,7 @@ w 1 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_14_0 2 -12 0 0 0 0 @@ -2382,7 +2383,7 @@ w 2 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_15_0 3 -12 0 0 0 0 @@ -2532,7 +2533,7 @@ w 3 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_16_0 4 -12 0 0 0 0 @@ -2682,7 +2683,7 @@ w 4 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_17_0 5 -12 0 0 0 0 @@ -2832,7 +2833,7 @@ w 5 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_18_0 6 -12 0 0 0 0 @@ -2982,7 +2983,7 @@ w 6 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_19_0 7 -12 0 0 0 0 @@ -3132,7 +3133,7 @@ w 7 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_20_0 8 -12 0 0 0 0 @@ -3282,7 +3283,7 @@ w 8 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_21_0 9 -12 0 0 0 0 @@ -3432,7 +3433,7 @@ w 9 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_22_0 10 -12 0 0 0 0 @@ -3582,7 +3583,7 @@ w 10 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_23_0 11 -12 0 0 0 0 @@ -3732,7 +3733,7 @@ w 11 12 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor -w + demo_actor_24_0 12 -12 0 0 0 0 @@ -3883,5 +3884,6 @@ w https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor + From ce57444b7492b70d141997c8d24b2126aa465a9e Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 10 Apr 2020 18:17:54 -0700 Subject: [PATCH 17/19] reduce number of actors --- examples/worlds/actor_crowd.sdf | 3506 +++---------------------------- 1 file changed, 241 insertions(+), 3265 deletions(-) diff --git a/examples/worlds/actor_crowd.sdf b/examples/worlds/actor_crowd.sdf index dcb5c5e834..6c216497b6 100644 --- a/examples/worlds/actor_crowd.sdf +++ b/examples/worlds/actor_crowd.sdf @@ -136,3751 +136,727 @@ demo_actor_0_0 - -12 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_1 - -12 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_2 - -12 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_3 - -12 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_4 - -12 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_5 - -12 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_6 - -12 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_7 - -12 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_8 - -12 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_9 - -12 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_10 - -12 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_11 - -12 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_12 - -12 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_13 - -12 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_14 - -12 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_15 - -12 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_16 - -12 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_17 - -12 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_18 - -12 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_19 - -12 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_20 - -12 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_21 - -12 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_22 - -12 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_23 - -12 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_0_24 - -12 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_0 - -11 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_1 - -11 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_2 - -11 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_3 - -11 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_4 - -11 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_5 - -11 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_6 - -11 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_7 - -11 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_8 - -11 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_9 - -11 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_10 - -11 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_11 - -11 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_12 - -11 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_13 - -11 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_14 - -11 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_15 - -11 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_16 - -11 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_17 - -11 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_18 - -11 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_19 - -11 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_20 - -11 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_21 - -11 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_22 - -11 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_23 - -11 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_1_24 - -11 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_0 - -10 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_1 - -10 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_2 - -10 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_3 - -10 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_4 - -10 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_5 - -10 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_6 - -10 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_7 - -10 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_8 - -10 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_9 - -10 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_10 - -10 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_11 - -10 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_12 - -10 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_13 - -10 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_14 - -10 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_15 - -10 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_16 - -10 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_17 - -10 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_18 - -10 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_19 - -10 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_20 - -10 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_21 - -10 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_22 - -10 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_23 - -10 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_2_24 - -10 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_0 - -9 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_1 - -9 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_2 - -9 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_3 - -9 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_4 - -9 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_5 - -9 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_6 - -9 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_7 - -9 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_8 - -9 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_9 - -9 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_10 - -9 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_11 - -9 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_12 - -9 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_13 - -9 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_14 - -9 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_15 - -9 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_16 - -9 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_17 - -9 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_18 - -9 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_19 - -9 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_20 - -9 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_21 - -9 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_22 - -9 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_23 - -9 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_3_24 - -9 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_0 - -8 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_1 - -8 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_2 - -8 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_3 - -8 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_4 - -8 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_5 - -8 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_6 - -8 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_7 - -8 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_8 - -8 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_9 - -8 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_10 - -8 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_11 - -8 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_12 - -8 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_13 - -8 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_14 - -8 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_15 - -8 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_16 - -8 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_17 - -8 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_18 - -8 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_19 - -8 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_20 - -8 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_21 - -8 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_22 - -8 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_23 - -8 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_4_24 - -8 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_0 - -7 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_1 - -7 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_2 - -7 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_3 - -7 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_4 - -7 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_5 - -7 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_6 - -7 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_7 - -7 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_8 - -7 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_9 - -7 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_10 - -7 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_11 - -7 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_12 - -7 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_13 - -7 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_14 - -7 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_15 - -7 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_16 - -7 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_17 - -7 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_18 - -7 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_19 - -7 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_20 - -7 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_21 - -7 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_22 - -7 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_23 - -7 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_5_24 - -7 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_0 - -6 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_1 - -6 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_2 - -6 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_3 - -6 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_4 - -6 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_5 - -6 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_6 - -6 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_7 - -6 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_8 - -6 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_9 - -6 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_10 - -6 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_11 - -6 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_12 - -6 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_13 - -6 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_14 - -6 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_15 - -6 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_16 - -6 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_17 - -6 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_18 - -6 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_19 - -6 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_20 - -6 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_21 - -6 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_22 - -6 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_23 - -6 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_6_24 - -6 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_0 - -5 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_1 - -5 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_2 - -5 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_3 - -5 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_4 - -5 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_5 - -5 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_6 - -5 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_7 - -5 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_8 - -5 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_9 - -5 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_10 - -5 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_11 - -5 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_12 - -5 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_13 - -5 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_14 - -5 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_15 - -5 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_16 - -5 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_17 - -5 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_18 - -5 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_19 - -5 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_20 - -5 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_21 - -5 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_22 - -5 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_23 - -5 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_7_24 - -5 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_0 - -4 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_1 - -4 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_2 - -4 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_3 - -4 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_4 - -4 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_5 - -4 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_6 - -4 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_7 - -4 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_8 - -4 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_9 - -4 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_10 - -4 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_11 - -4 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_12 - -4 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_13 - -4 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_14 - -4 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_15 - -4 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_16 - -4 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_17 - -4 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_18 - -4 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_19 - -4 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_20 - -4 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_21 - -4 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_22 - -4 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_23 - -4 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_8_24 - -4 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_0 - -3 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_1 - -3 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_2 - -3 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_3 - -3 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_4 - -3 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_5 - -3 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_6 - -3 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_7 - -3 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_8 - -3 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_9 - -3 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_10 - -3 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_11 - -3 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_12 - -3 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_13 - -3 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_14 - -3 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_15 - -3 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_16 - -3 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_17 - -3 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_18 - -3 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_19 - -3 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_20 - -3 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_21 - -3 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_22 - -3 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_23 - -3 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_9_24 - -3 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_0 - -2 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_1 - -2 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_2 - -2 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_3 - -2 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_4 - -2 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_5 - -2 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_6 - -2 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_7 - -2 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_8 - -2 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_9 - -2 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_10 - -2 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_11 - -2 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_12 - -2 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_13 - -2 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_14 - -2 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_15 - -2 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_16 - -2 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_17 - -2 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_18 - -2 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_19 - -2 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_20 - -2 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_21 - -2 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_22 - -2 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_23 - -2 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_10_24 - -2 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_0 - -1 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_1 - -1 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_2 - -1 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_3 - -1 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_4 - -1 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_5 - -1 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_6 - -1 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_7 - -1 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_8 - -1 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_9 - -1 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_10 - -1 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_11 - -1 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_12 - -1 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_13 - -1 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_14 - -1 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_15 - -1 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_16 - -1 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_17 - -1 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_18 - -1 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_19 - -1 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_20 - -1 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_21 - -1 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_22 - -1 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_23 - -1 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_11_24 - -1 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_0 - 0 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_1 - 0 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_2 - 0 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_3 - 0 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_4 - 0 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_5 - 0 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_6 - 0 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_7 - 0 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_8 - 0 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_9 - 0 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_10 - 0 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_11 - 0 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_12 - 0 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_13 - 0 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_14 - 0 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_15 - 0 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_16 - 0 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_17 - 0 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_18 - 0 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_19 - 0 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_20 - 0 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_21 - 0 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_22 - 0 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_23 - 0 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_12_24 - 0 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_0 - 1 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_1 - 1 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_2 - 1 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_3 - 1 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_4 - 1 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_5 - 1 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_6 - 1 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_7 - 1 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_8 - 1 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_9 - 1 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_10 - 1 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_11 - 1 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_12 - 1 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_13 - 1 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_14 - 1 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_15 - 1 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_16 - 1 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_17 - 1 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_18 - 1 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_19 - 1 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_20 - 1 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_21 - 1 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_22 - 1 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_23 - 1 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_13_24 - 1 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_0 - 2 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_1 - 2 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_2 - 2 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_3 - 2 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_4 - 2 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_5 - 2 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_6 - 2 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_7 - 2 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_8 - 2 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_9 - 2 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_10 - 2 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_11 - 2 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_12 - 2 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_13 - 2 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_14 - 2 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_15 - 2 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_16 - 2 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_17 - 2 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_18 - 2 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_19 - 2 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_20 - 2 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_21 - 2 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_22 - 2 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_23 - 2 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_14_24 - 2 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_0 - 3 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_1 - 3 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_2 - 3 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_3 - 3 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_4 - 3 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_5 - 3 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_6 - 3 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_7 - 3 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_8 - 3 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_9 - 3 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_10 - 3 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_11 - 3 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_12 - 3 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_13 - 3 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_14 - 3 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_15 - 3 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_16 - 3 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_17 - 3 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_18 - 3 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_19 - 3 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_20 - 3 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_21 - 3 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_22 - 3 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_23 - 3 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_15_24 - 3 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_0 - 4 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_1 - 4 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_2 - 4 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_3 - 4 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_4 - 4 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_5 - 4 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_6 - 4 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_7 - 4 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_8 - 4 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_9 - 4 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_10 - 4 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_11 - 4 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_12 - 4 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_13 - 4 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_14 - 4 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_15 - 4 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_16 - 4 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_17 - 4 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_18 - 4 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_19 - 4 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_20 - 4 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_21 - 4 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_22 - 4 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_23 - 4 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_16_24 - 4 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_0 - 5 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_1 - 5 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_2 - 5 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_3 - 5 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_4 - 5 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_5 - 5 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_6 - 5 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_7 - 5 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_8 - 5 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_9 - 5 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_10 - 5 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_11 - 5 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_12 - 5 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_13 - 5 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_14 - 5 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_15 - 5 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_16 - 5 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_17 - 5 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_18 - 5 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_19 - 5 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_20 - 5 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_21 - 5 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_22 - 5 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_23 - 5 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_17_24 - 5 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_0 - 6 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_1 - 6 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_2 - 6 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_3 - 6 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_4 - 6 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_5 - 6 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_6 - 6 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_7 - 6 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_8 - 6 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_9 - 6 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_10 - 6 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_11 - 6 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_12 - 6 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_13 - 6 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_14 - 6 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_15 - 6 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_16 - 6 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_17 - 6 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_18 - 6 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_19 - 6 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_20 - 6 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_21 - 6 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_22 - 6 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_23 - 6 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_18_24 - 6 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_0 - 7 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_1 - 7 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_2 - 7 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_3 - 7 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_4 - 7 -8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_5 - 7 -7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_6 - 7 -6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_7 - 7 -5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_8 - 7 -4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_9 - 7 -3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_10 - 7 -2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_11 - 7 -1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_12 - 7 0 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_13 - 7 1 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_14 - 7 2 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_15 - 7 3 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_16 - 7 4 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_17 - 7 5 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_18 - 7 6 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_19 - 7 7 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_20 - 7 8 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_21 - 7 9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_22 - 7 10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_23 - 7 11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_19_24 - 7 12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_20_0 - 8 -12 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_20_1 - 8 -11 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_20_2 - 8 -10 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_20_3 - 8 -9 0 0 0 0 - https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - - - - demo_actor_20_4 - 8 -8 0 0 0 0 + -5 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_5 - 8 -7 0 0 0 0 + demo_actor_0_1 + -5 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_6 - 8 -6 0 0 0 0 + demo_actor_0_2 + -5 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_7 - 8 -5 0 0 0 0 + demo_actor_0_3 + -5 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_8 - 8 -4 0 0 0 0 + demo_actor_0_4 + -5 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_9 - 8 -3 0 0 0 0 + demo_actor_0_5 + -5 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_10 - 8 -2 0 0 0 0 + demo_actor_0_6 + -5 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_11 - 8 -1 0 0 0 0 + demo_actor_0_7 + -5 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_12 - 8 0 0 0 0 0 + demo_actor_0_8 + -5 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_13 - 8 1 0 0 0 0 + demo_actor_0_9 + -5 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_14 - 8 2 0 0 0 0 + demo_actor_0_10 + -5 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_15 - 8 3 0 0 0 0 + demo_actor_1_0 + -4 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_16 - 8 4 0 0 0 0 + demo_actor_1_1 + -4 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_17 - 8 5 0 0 0 0 + demo_actor_1_2 + -4 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_18 - 8 6 0 0 0 0 + demo_actor_1_3 + -4 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_19 - 8 7 0 0 0 0 + demo_actor_1_4 + -4 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_20 - 8 8 0 0 0 0 + demo_actor_1_5 + -4 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_21 - 8 9 0 0 0 0 + demo_actor_1_6 + -4 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_22 - 8 10 0 0 0 0 + demo_actor_1_7 + -4 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_23 - 8 11 0 0 0 0 + demo_actor_1_8 + -4 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_20_24 - 8 12 0 0 0 0 + demo_actor_1_9 + -4 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_0 - 9 -12 0 0 0 0 + demo_actor_1_10 + -4 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_1 - 9 -11 0 0 0 0 + demo_actor_2_0 + -3 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_2 - 9 -10 0 0 0 0 + demo_actor_2_1 + -3 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_3 - 9 -9 0 0 0 0 + demo_actor_2_2 + -3 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_4 - 9 -8 0 0 0 0 + demo_actor_2_3 + -3 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_5 - 9 -7 0 0 0 0 + demo_actor_2_4 + -3 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_6 - 9 -6 0 0 0 0 + demo_actor_2_5 + -3 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_7 - 9 -5 0 0 0 0 + demo_actor_2_6 + -3 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_8 - 9 -4 0 0 0 0 + demo_actor_2_7 + -3 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_9 - 9 -3 0 0 0 0 + demo_actor_2_8 + -3 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_10 - 9 -2 0 0 0 0 + demo_actor_2_9 + -3 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_11 - 9 -1 0 0 0 0 + demo_actor_2_10 + -3 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_12 - 9 0 0 0 0 0 + demo_actor_3_0 + -2 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_13 - 9 1 0 0 0 0 + demo_actor_3_1 + -2 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_14 - 9 2 0 0 0 0 + demo_actor_3_2 + -2 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_15 - 9 3 0 0 0 0 + demo_actor_3_3 + -2 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_16 - 9 4 0 0 0 0 + demo_actor_3_4 + -2 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_17 - 9 5 0 0 0 0 + demo_actor_3_5 + -2 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_18 - 9 6 0 0 0 0 + demo_actor_3_6 + -2 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_19 - 9 7 0 0 0 0 + demo_actor_3_7 + -2 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_20 - 9 8 0 0 0 0 + demo_actor_3_8 + -2 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_21 - 9 9 0 0 0 0 + demo_actor_3_9 + -2 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_22 - 9 10 0 0 0 0 + demo_actor_3_10 + -2 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_23 - 9 11 0 0 0 0 + demo_actor_4_0 + -1 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_21_24 - 9 12 0 0 0 0 + demo_actor_4_1 + -1 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_0 - 10 -12 0 0 0 0 + demo_actor_4_2 + -1 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_1 - 10 -11 0 0 0 0 + demo_actor_4_3 + -1 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_2 - 10 -10 0 0 0 0 + demo_actor_4_4 + -1 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_3 - 10 -9 0 0 0 0 + demo_actor_4_5 + -1 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_4 - 10 -8 0 0 0 0 + demo_actor_4_6 + -1 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_5 - 10 -7 0 0 0 0 + demo_actor_4_7 + -1 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_6 - 10 -6 0 0 0 0 + demo_actor_4_8 + -1 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_7 - 10 -5 0 0 0 0 + demo_actor_4_9 + -1 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_8 - 10 -4 0 0 0 0 + demo_actor_4_10 + -1 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_9 - 10 -3 0 0 0 0 + demo_actor_5_0 + 0 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_10 - 10 -2 0 0 0 0 + demo_actor_5_1 + 0 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_11 - 10 -1 0 0 0 0 + demo_actor_5_2 + 0 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_12 - 10 0 0 0 0 0 + demo_actor_5_3 + 0 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_13 - 10 1 0 0 0 0 + demo_actor_5_4 + 0 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_14 - 10 2 0 0 0 0 + demo_actor_5_5 + 0 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_15 - 10 3 0 0 0 0 + demo_actor_5_6 + 0 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_16 - 10 4 0 0 0 0 + demo_actor_5_7 + 0 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_17 - 10 5 0 0 0 0 + demo_actor_5_8 + 0 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_18 - 10 6 0 0 0 0 + demo_actor_5_9 + 0 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_19 - 10 7 0 0 0 0 + demo_actor_5_10 + 0 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_20 - 10 8 0 0 0 0 + demo_actor_6_0 + 1 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_21 - 10 9 0 0 0 0 + demo_actor_6_1 + 1 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_22 - 10 10 0 0 0 0 + demo_actor_6_2 + 1 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_23 - 10 11 0 0 0 0 + demo_actor_6_3 + 1 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_22_24 - 10 12 0 0 0 0 + demo_actor_6_4 + 1 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_0 - 11 -12 0 0 0 0 + demo_actor_6_5 + 1 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_1 - 11 -11 0 0 0 0 + demo_actor_6_6 + 1 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_2 - 11 -10 0 0 0 0 + demo_actor_6_7 + 1 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_3 - 11 -9 0 0 0 0 + demo_actor_6_8 + 1 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_4 - 11 -8 0 0 0 0 + demo_actor_6_9 + 1 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_5 - 11 -7 0 0 0 0 + demo_actor_6_10 + 1 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_6 - 11 -6 0 0 0 0 + demo_actor_7_0 + 2 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_7 - 11 -5 0 0 0 0 + demo_actor_7_1 + 2 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_8 - 11 -4 0 0 0 0 + demo_actor_7_2 + 2 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_9 - 11 -3 0 0 0 0 + demo_actor_7_3 + 2 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_10 - 11 -2 0 0 0 0 + demo_actor_7_4 + 2 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_11 - 11 -1 0 0 0 0 + demo_actor_7_5 + 2 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_12 - 11 0 0 0 0 0 + demo_actor_7_6 + 2 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_13 - 11 1 0 0 0 0 + demo_actor_7_7 + 2 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_14 - 11 2 0 0 0 0 + demo_actor_7_8 + 2 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_15 - 11 3 0 0 0 0 + demo_actor_7_9 + 2 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_16 - 11 4 0 0 0 0 + demo_actor_7_10 + 2 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_17 - 11 5 0 0 0 0 + demo_actor_8_0 + 3 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_18 - 11 6 0 0 0 0 + demo_actor_8_1 + 3 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_19 - 11 7 0 0 0 0 + demo_actor_8_2 + 3 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_20 - 11 8 0 0 0 0 + demo_actor_8_3 + 3 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_21 - 11 9 0 0 0 0 + demo_actor_8_4 + 3 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_22 - 11 10 0 0 0 0 + demo_actor_8_5 + 3 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_23 - 11 11 0 0 0 0 + demo_actor_8_6 + 3 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_23_24 - 11 12 0 0 0 0 + demo_actor_8_7 + 3 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_0 - 12 -12 0 0 0 0 + demo_actor_8_8 + 3 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_1 - 12 -11 0 0 0 0 + demo_actor_8_9 + 3 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_2 - 12 -10 0 0 0 0 + demo_actor_8_10 + 3 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_3 - 12 -9 0 0 0 0 + demo_actor_9_0 + 4 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_4 - 12 -8 0 0 0 0 + demo_actor_9_1 + 4 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_5 - 12 -7 0 0 0 0 + demo_actor_9_2 + 4 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_6 - 12 -6 0 0 0 0 + demo_actor_9_3 + 4 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_7 - 12 -5 0 0 0 0 + demo_actor_9_4 + 4 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_8 - 12 -4 0 0 0 0 + demo_actor_9_5 + 4 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_9 - 12 -3 0 0 0 0 + demo_actor_9_6 + 4 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_10 - 12 -2 0 0 0 0 + demo_actor_9_7 + 4 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_11 - 12 -1 0 0 0 0 + demo_actor_9_8 + 4 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_12 - 12 0 0 0 0 0 + demo_actor_9_9 + 4 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_13 - 12 1 0 0 0 0 + demo_actor_9_10 + 4 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_14 - 12 2 0 0 0 0 + demo_actor_10_0 + 5 -5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_15 - 12 3 0 0 0 0 + demo_actor_10_1 + 5 -4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_16 - 12 4 0 0 0 0 + demo_actor_10_2 + 5 -3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_17 - 12 5 0 0 0 0 + demo_actor_10_3 + 5 -2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_18 - 12 6 0 0 0 0 + demo_actor_10_4 + 5 -1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_19 - 12 7 0 0 0 0 + demo_actor_10_5 + 5 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_20 - 12 8 0 0 0 0 + demo_actor_10_6 + 5 1 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_21 - 12 9 0 0 0 0 + demo_actor_10_7 + 5 2 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_22 - 12 10 0 0 0 0 + demo_actor_10_8 + 5 3 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_23 - 12 11 0 0 0 0 + demo_actor_10_9 + 5 4 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor - demo_actor_24_24 - 12 12 0 0 0 0 + demo_actor_10_10 + 5 5 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/Mingfei/models/actor From d35b865ad12d69ead44de17c2e98d586d1dc8dbe Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 10 Apr 2020 21:01:10 -0700 Subject: [PATCH 18/19] remove unused var --- src/rendering/SceneManager.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 390879684c..1e68948fc1 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -975,7 +975,6 @@ AnimationUpdateData SceneManager::ActorAnimationAt( std::chrono::steady_clock::duration>( std::chrono::duration(time)); } - std::string skinName = skel->NodeNameAnimToSkin(animIndex, rootNodeName); math::Matrix4d skinTf = skel->AlignTranslation(animIndex, rootNodeName) * rawFrame * skel->AlignRotation(animIndex, rootNodeName); From b353d096070b654ea6b684150ce9d4e8d5668199 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Sat, 11 Apr 2020 05:50:06 +0000 Subject: [PATCH 19/19] Close branch skel_animation