Browse Source

Add Pheromone, Colony, and Habitat classes

master
C. J. Howard 7 years ago
parent
commit
304e290ca3
18 changed files with 637 additions and 123 deletions
  1. +6
    -0
      CMakeLists.txt
  2. +1
    -1
      data
  3. +1
    -1
      lib/emergent
  4. +72
    -7
      src/game/agent.cpp
  5. +17
    -1
      src/game/agent.hpp
  6. +102
    -37
      src/game/ant.cpp
  7. +2
    -41
      src/game/ant.hpp
  8. +74
    -0
      src/game/colony.cpp
  9. +96
    -0
      src/game/colony.hpp
  10. +34
    -0
      src/game/habitat.cpp
  11. +48
    -0
      src/game/habitat.hpp
  12. +10
    -1
      src/game/navmesh.cpp
  13. +50
    -0
      src/game/pheromone.cpp
  14. +71
    -0
      src/game/pheromone.hpp
  15. +2
    -2
      src/states/splash-state.cpp
  16. +44
    -31
      src/states/title-state.cpp
  17. +1
    -0
      src/states/title-state.hpp
  18. +6
    -1
      src/ui/ui.cpp

+ 6
- 0
CMakeLists.txt View File

@ -113,10 +113,16 @@ set(EXECUTABLE_SOURCES
${EXECUTABLE_SOURCE_DIR}/game/ant.cpp
${EXECUTABLE_SOURCE_DIR}/game/agent.hpp
${EXECUTABLE_SOURCE_DIR}/game/agent.cpp
${EXECUTABLE_SOURCE_DIR}/game/colony.hpp
${EXECUTABLE_SOURCE_DIR}/game/colony.cpp
${EXECUTABLE_SOURCE_DIR}/game/habitat.hpp
${EXECUTABLE_SOURCE_DIR}/game/habitat.cpp
${EXECUTABLE_SOURCE_DIR}/game/nest.hpp
${EXECUTABLE_SOURCE_DIR}/game/nest.cpp
${EXECUTABLE_SOURCE_DIR}/game/navmesh.hpp
${EXECUTABLE_SOURCE_DIR}/game/navmesh.cpp
${EXECUTABLE_SOURCE_DIR}/game/pheromone.cpp
${EXECUTABLE_SOURCE_DIR}/game/pheromone.cpp
${EXECUTABLE_SOURCE_DIR}/debug.hpp
${EXECUTABLE_SOURCE_DIR}/debug.cpp
${EXECUTABLE_SOURCE_DIR}/camera-controller.hpp

+ 1
- 1
data

@ -1 +1 @@
Subproject commit 37456bb0933b6eed8444f2d6f1ce0819bac00b15
Subproject commit 935cc4cf3090766c657eb1f11b6c26adb164a325

+ 1
- 1
lib/emergent

@ -1 +1 @@
Subproject commit 341a6cd0b704379cd38c9382f9ea0ef4b33a382a
Subproject commit af599983ef5650ef399fb30dc985a98f436b5db0

+ 72
- 7
src/game/agent.cpp View File

@ -27,7 +27,8 @@ Agent::Agent():
up(0, 1, 0),
right(1, 0, 0),
rotation(1, 0, 0, 0),
wanderDirection(0, 0, -1)
wanderDirection(0, 0, -1),
velocity(0.0f)
{}
void Agent::applyForce(const Vector3& force)
@ -50,27 +51,27 @@ void Agent::updateVelocity()
Vector3 Agent::wander(float dt)
{
// Calculate center of wander circle
Vector3 wanderCircleCenter = forward * wanderCircleDistance;
Vector3 wanderCircleCenter = position + forward * wanderCircleDistance;
// Calculate wander force
Vector3 force = wanderCircleCenter + wanderDirection * wanderCircleRadius;
Vector3 target = wanderCircleCenter + wanderDirection * wanderCircleRadius;
// Rotate wander direction by a random displacement angle
float displacement = frand(-wanderRate * 0.5f, wanderRate * 0.5f);
wanderDirection = glm::normalize(glm::angleAxis(displacement, up) * wanderDirection);
return force;
return seek(target);
}
Vector3 Agent::seek(const Vector3& target) const
{
Vector3 desiredVelocity = glm::normalize(position - target) * maxSpeed;
Vector3 desiredVelocity = glm::normalize(target - position) * maxSpeed;
return desiredVelocity - velocity;
}
Vector3 Agent::flee(const Vector3& target) const
{
Vector3 desiredVelocity = glm::normalize(target - position) * maxSpeed;
Vector3 desiredVelocity = glm::normalize(position - target) * maxSpeed;
return desiredVelocity - velocity;
}
@ -92,6 +93,22 @@ Vector3 Agent::containment(const Vector3& probe) const
return Vector3(0.0f);
}
/*
// Calculate difference between probe position and position on edge
Vector3 end = cartesian(step.end,
step.triangle->edge->vertex->position,
step.triangle->edge->next->vertex->position,
step.triangle->edge->previous->vertex->position);
Vector3 difference = probe - end;
float depth = 0.0f;
if (nonzero(difference))
{
depth = glm::length(difference);
}
*/
// Calculate edge normal
const Vector3& a = step.edge->vertex->position;
const Vector3& b = step.edge->next->vertex->position;
@ -99,7 +116,39 @@ Vector3 Agent::containment(const Vector3& probe) const
Vector3 edgeNormal = glm::cross(up, ab);
// Calculate reflection vector of forward vector and edge normal
Vector3 force = glm::reflect(forward, edgeNormal);
//Vector3 reflection = glm::reflect(forward, edgeNormal);
/*
Vector3 target = cartesian(step.end,
step.triangle->edge->vertex->position,
step.triangle->edge->next->vertex->position,
step.triangle->edge->previous->vertex->position) + reflection * 0.1f;
*/
//std::cout << "reflection: " << reflection.x << ", " << reflection.y << ", " << reflection.z << std::endl;
return edgeNormal;
}
Vector3 Agent::separation(const std::list<Agent*>& neighbors) const
{
Vector3 force(0.0f);
for (Agent* neighbor: neighbors)
{
Vector3 difference = position - neighbor->position;
float distanceSquared = glm::dot(difference, difference);
if (distanceSquared > 0.0f && distanceSquared < separationRadiusSquared)
{
force += difference * (1.0f / distanceSquared);
}
}
if (nonzero(force))
{
force = glm::normalize(force);
}
return force;
}
@ -134,6 +183,16 @@ void Agent::setOrientation(const Vector3& newForward, const Vector3& newUp)
wanderDirection = glm::normalize(project_on_plane(alignment * wanderDirection, Vector3(0.0f), up));
}
void Agent::setMaxSpeed(float speed)
{
maxSpeed = speed;
}
void Agent::setVelocity(const Vector3& velocity)
{
this->velocity = velocity;
}
void Agent::setWanderCircleDistance(float distance)
{
wanderCircleDistance = distance;
@ -149,6 +208,12 @@ void Agent::setWanderRate(float angle)
wanderRate = angle;
}
void Agent::setSeparationRadius(float radius)
{
separationRadius = radius;
separationRadiusSquared = separationRadius * separationRadius;
}
/** EXAMPLE USAGE
Vector3 wanderForce = wander(dt) * wanderWeight;
Vector3 fleeForce = flee(mouse) * fleeWeight;

+ 17
- 1
src/game/agent.hpp View File

@ -83,12 +83,19 @@ public:
Vector3 containment(const Vector3& probe) const;
Vector3 separation(const std::list<Agent*>& neighbors) const;
Vector3 forage(const Vector3& leftProbe, const Vector3& rightProbe);
void setMaxSpeed(float speed);
void setVelocity(const Vector3& velocity);
void setMaxAcceleration(float acceleration);
void setMass(float mass);
void setWanderCircleDistance(float distance);
void setWanderCircleRadius(float radius);
void setWanderRate(float angle);
void setSeparationRadius(float radius);
/**
* Sets the position of the agent on a navmesh.
@ -111,7 +118,7 @@ public:
// or
Vector3 followEdge();
Vector3 avoidObstacle(const Obstacle* obstacle);
Vector3 separation(const std::vector<const Agent*>* neighbors);
Vector3 alignment(const std::vector<const Agent*>* neighbors);
Vector3 cohesion(const std::vector<const Agent*>* neighbors);
*/
@ -124,6 +131,8 @@ public:
const Vector3& getUp() const;
const Vector3& getRight() const;
const Quaternion& getRotation() const;
const Vector3& getVelocity() const;
private:
Navmesh::Triangle* navmeshTriangle;
@ -148,6 +157,8 @@ private:
float wanderCircleRadius;
float wanderRate;
Vector3 wanderDirection;
float separationRadius;
float separationRadiusSquared;
};
inline const Navmesh::Triangle* Agent::getNavmeshTriangle() const
@ -190,4 +201,9 @@ inline const Quaternion& Agent::getRotation() const
return rotation;
}
inline const Vector3& Agent::getVelocity() const
{
return velocity;
}
#endif // AGENT_HPP

+ 102
- 37
src/game/ant.cpp View File

@ -18,6 +18,8 @@
*/
#include "ant.hpp"
#include "colony.hpp"
#include "pheromone.hpp"
Ant::Ant(Colony* colony):
colony(colony),
@ -61,37 +63,78 @@ void Ant::turn(float angle)
void Ant::update(float dt)
{
float probeLateralOffset = 0.1f;
float probeForwardOffset = 0.3f;
// Steering
if (state == Ant::State::WANDER)
{
setWanderCircleDistance(3.0f);
setWanderCircleRadius(0.25f);
setWanderCircleDistance(4.0f);
setWanderCircleRadius(0.3f);
setWanderRate(glm::radians(90.0f));
setSeparationRadius(0.5f);
setMaxSpeed(0.025f);
// Calculate wander force
Vector3 wanderForce = wander(dt);
// Setup containment probes
float probeLateralOffset = 0.35f;
Vector3 forwardProbe = getForward() * 0.5f;
Vector3 leftProbe = getForward() * 0.1f - getRight() * probeLateralOffset;
Vector3 rightProbe = getForward() * 0.1f + getRight() * probeLateralOffset;
Vector3 leftProbe = getForward() * probeForwardOffset - getRight() * probeLateralOffset;
Vector3 rightProbe = getForward() * probeForwardOffset + getRight() * probeLateralOffset;
// Calculate containment force
Vector3 containmentForce = containment(forwardProbe)
+ containment(leftProbe)
+ containment(rightProbe);
Vector3 containmentForce = containment(leftProbe) + containment(rightProbe);
// Determine neighbors
float neighborhoodSize = 2.0f;
AABB neighborhoodAABB(getPosition() - Vector3(neighborhoodSize * 0.5f), getPosition() + Vector3(neighborhoodSize * 0.5f));
std::list<Agent*> neighbors;
colony->queryAnts(neighborhoodAABB, &neighbors);
// Calculate separation force
Vector3 separationForce = separation(neighbors);
// Calculate velocity
Vector3 velocity(0.0f);
Vector3 velocity = getVelocity();
velocity += wanderForce;
velocity += containmentForce;
velocity += containmentForce * 0.0025f;
velocity += separationForce * 0.01f;
velocity = limit(velocity, 0.025f);
setVelocity(velocity);
setOrientation(glm::normalize(velocity), getUp());
// Move ant
move(velocity);
}
else
{
Vector3 leftProbe = getForward() * probeForwardOffset - getRight() * probeLateralOffset;
Vector3 rightProbe = getForward() * probeForwardOffset + getRight() * probeLateralOffset;
Vector3 containmentForce = containment(leftProbe) + containment(rightProbe);
Vector3 velocity = Vector3(0.0f);
velocity += containmentForce;
velocity = limit(velocity, 0.025f);
setVelocity(velocity);
//setOrientation(glm::normalize(velocity), getUp());
// Move ant
move(velocity);
}
// Locomotion
/*
As the ant moves forward, legs in the stance phase are kept grounded via IK. If IK constraints are violated, the swinging legs are grounded
and the grounded legs begin swinging.
Two poses are loaded from the model file: midswing and touchdown.
touchdown is the pose in which all legs are at the end of their swing phases and need to be grounded
midswing is the pose in which all legs are at the highest point in their swing phases
when a grounded leg enters the swing phases, its current pose is saved as the liftoff pose, then an animation is created using the liftoff pose, midswing pose, and touchdown pose.
*/
// Update transform
transform.translation = getPosition();
@ -101,38 +144,60 @@ void Ant::update(float dt)
modelInstance.setTransform(transform);
}
void Ant::setState(Ant::State state)
{
this->state = state;
}
Colony::Colony():
antModel(nullptr)
{}
Ant* Colony::spawn(Navmesh* navmesh, Navmesh::Triangle* triangle, const Vector3& position)
Vector3 Ant::forage(const Vector3& leftReceptor, const Vector3& rightReceptor)
{
// Allocate ant
Ant* ant = new Ant(this);
// Position it on the navmesh
ant->setPosition(triangle, position);
float leftSignal = 0.0f;
float rightSignal = 0.0f;
// Add ant to the colony
ants.push_back(ant);
// Detect pheromones with left receptor
std::list<Pheromone*> leftPheromones;
colony->getPheromoneOctree()->query(AABB(leftReceptor, leftReceptor), &leftPheromones);
for (Pheromone* pheromone: leftPheromones)
{
Vector3 difference = pheromone->getPosition() - rightReceptor;
float distanceSquared = glm::dot(difference, difference);
if (distanceSquared <= pheromone->getRadiusSquared())
{
// Calculate attenuated pheromone strength using inverse-square law
float strength = pheromone->getStrength() / ((distanceSquared == 0.0f) ? 1.0f : distanceSquared);
leftSignal += strength;
}
}
return ant;
}
void Colony::update(float dt)
{
for (Ant* ant: ants)
// Detect pheromones with right receptor
std::list<Pheromone*> rightPheromones;
colony->getPheromoneOctree()->query(AABB(rightReceptor, rightReceptor), &rightPheromones);
for (Pheromone* pheromone: rightPheromones)
{
ant->update(dt);
Vector3 difference = pheromone->getPosition() - rightReceptor;
float distanceSquared = glm::dot(difference, difference);
if (distanceSquared <= pheromone->getRadiusSquared())
{
// Calculate attenuated pheromone strength using inverse-square law
float strength = pheromone->getStrength() / ((distanceSquared == 0.0f) ? 1.0f : distanceSquared);
rightSignal += strength;
}
}
// Add noise
const float maxNoise = 0.1f;
leftSignal += frand(0.0f, maxNoise);
rightSignal += frand(0.0f, maxNoise);
if (leftSignal + rightSignal > 0.0f)
{
const float maxPheromoneTurningAngle = 0.1f;
// Use Weber's law (Perna et al.) to calculate turning angle based on pheromone signals
float turningAngle = maxPheromoneTurningAngle * ((leftSignal - rightSignal) / (leftSignal + rightSignal));
}
return Vector3(0.0f);
}
void Colony::setAntModel(Model* model)
void Ant::setState(Ant::State state)
{
this->antModel = model;
this->state = state;
}

+ 2
- 41
src/game/ant.hpp View File

@ -81,6 +81,8 @@ public:
ModelInstance* getModelInstance();
private:
Vector3 forage(const Vector3& leftReceptor, const Vector3& rightReceptor);
/**
* Calculates the surface normal averaged between the surface normals at each of the ant's grounded feet.
*/
@ -121,45 +123,4 @@ inline ModelInstance* Ant::getModelInstance()
return &modelInstance;
}
/**
* A colony of ants.
*/
class Colony
{
public:
Colony();
Ant* spawn(Navmesh* navmesh, Navmesh::Triangle* triangle, const Vector3& position);
void update(float dt);
void setAntModel(Model* model);
const Model* getAntModel() const;
Model* getAntModel();
private:
// Rendering
Model* antModel;
// Locomotion
float walkSpeed;
float turnSpeed;
Gait* tripodGait;
Gait* rippleGait;
Gait* slowWaveGait;
std::vector<Ant*> ants;
};
inline const Model* Colony::getAntModel() const
{
return antModel;
}
inline Model* Colony::getAntModel()
{
return antModel;
}
#endif // ANT_HPP

+ 74
- 0
src/game/colony.cpp View File

@ -0,0 +1,74 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#include "colony.hpp"
#include "ant.hpp"
#include "pheromone.hpp"
Colony::Colony():
antModel(nullptr)
{
antOctree = new Octree<Agent*>(AABB(Vector3(-8.0f), Vector3(8.0f)), 5);
pheromoneOctree = new Octree<Pheromone*>(AABB(Vector3(-8.0f), Vector3(8.0f)), 5);
}
Colony::~Colony()
{
delete antOctree;
}
Ant* Colony::spawn(Navmesh* navmesh, Navmesh::Triangle* triangle, const Vector3& position)
{
// Allocate ant
Ant* ant = new Ant(this);
// Position it on the navmesh
ant->setPosition(triangle, position);
// Add ant to the colony
ants.push_back(ant);
return ant;
}
void Colony::update(float dt)
{
// Rebuild octree
antOctree->clear();
for (Ant* ant: ants)
{
antOctree->insert(AABB(ant->getPosition(), ant->getPosition()), ant);
}
// Update ants
for (Ant* ant: ants)
{
ant->update(dt);
}
}
void Colony::setAntModel(Model* model)
{
this->antModel = model;
}
void Colony::queryAnts(const BoundingVolume& volume, std::list<Agent*>* results) const
{
antOctree->query(volume, results);
}

+ 96
- 0
src/game/colony.hpp View File

@ -0,0 +1,96 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef COLONY_HPP
#define COLONY_HPP
#include <vector>
#include "navmesh.hpp"
#include <emergent/emergent.hpp>
using namespace Emergent;
class Ant;
class Agent;
class Pheromone;
class Gait;
/**
* A colony of ants.
*/
class Colony
{
public:
Colony();
~Colony();
Ant* spawn(Navmesh* navmesh, Navmesh::Triangle* triangle, const Vector3& position);
void update(float dt);
void setAntModel(Model* model);
const Model* getAntModel() const;
Model* getAntModel();
void queryAnts(const BoundingVolume& volume, std::list<Agent*>* results) const;
const Octree<Agent*>* getAntOctree() const;
const Octree<Pheromone*>* getPheromoneOctree() const;
private:
// Rendering
Model* antModel;
// Locomotion
float walkSpeed;
float turnSpeed;
Gait* tripodGait;
Gait* rippleGait;
Gait* slowWaveGait;
std::vector<Ant*> ants;
Octree<Agent*>* antOctree;
std::vector<Pheromone*> pheromones;
Octree<Pheromone*>* pheromoneOctree;
};
inline const Model* Colony::getAntModel() const
{
return antModel;
}
inline Model* Colony::getAntModel()
{
return antModel;
}
inline const Octree<Agent*>* Colony::getAntOctree() const
{
return antOctree;
}
inline const Octree<Pheromone*>* Colony::getPheromoneOctree() const
{
return pheromoneOctree;
}
#endif // COLONY_HPP

+ 34
- 0
src/game/habitat.cpp View File

@ -0,0 +1,34 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#include "habitat.hpp"
Habitat::Habitat(const AABB& bounds, int maxOctreeDepth)
{
obstacleOctree = new Octree<Navmesh*>(bounds, maxOctreeDepth);
pheromoneOctree = new Octree<Pheromone*>(bounds, maxOctreeDepth);
agentOctree = new Octree<Agent*>(bounds, maxOctreeDepth);
}
Habitat::~Habitat()
{
delete obstacleOctree;
delete pheromoneOctree;
delete agentOctree;
}

+ 48
- 0
src/game/habitat.hpp View File

@ -0,0 +1,48 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef HABITAT_HPP
#define HABITAT_HPP
#include <vector>
#include <emergent/emergent.hpp>
using namespace Emergent;
class Navmesh;
class Pheromone;
class Agent;
class Habitat
{
public:
Habitat(const AABB& bounds, int maxOctreeDepth);
~Habitat();
const Octree<Navmesh*>* getObstacleOctree() const;
const Octree<Pheromone*>* getPheromoneOctree() const;
const Octree<Agent*>* getAgentOctree() const;
private:
Octree<Navmesh*>* obstacleOctree;
Octree<Pheromone*>* pheromoneOctree;
Octree<Agent*>* agentOctree;
};
#endif // HABITAT_HPP

+ 10
- 1
src/game/navmesh.cpp View File

@ -193,7 +193,7 @@ void Navmesh::traverse(Navmesh::Triangle* startTriangle, const Vector3& startPos
// Set initial velocity
Vector3 velocity = startVelocity;
// Traverse navmesh
float distance = 0.0f;
while (distance < maxDistance)
@ -250,6 +250,15 @@ void Navmesh::traverse(Navmesh::Triangle* startTriangle, const Vector3& startPos
// Move to the next triangle
step.triangle = step.edge->symmetric->triangle;
// Ensure triangle wasn't already visited
for (const Step& visited: (*traversal))
{
if (step.triangle == visited.triangle)
{
return;
}
}
// Calculate barycentric starting coordinates of the next step
step.start = normalize_barycentric(barycentric(cartesianEnd,
step.triangle->edge->vertex->position,

+ 50
- 0
src/game/pheromone.cpp View File

@ -0,0 +1,50 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#include "pheromone.hpp"
#include <cmath>
void Pheromone::setStrength(float strength)
{
this->strength = strength;
// Calculate approximate radius
const float minimumStrength = 0.01f; // Pheromone strength epsilon
const float quadraticAttenuation = 1.0f; // Quadratic attenuation factor (1.0 = inverse-square falloff)
radiusSquared = strength / (quadraticAttenuation * minimumStrength);
radius = std::sqrt(radiusSquared);
}
float Pheromone::getAttenuatedStrength(const Vector3& position) const
{
Vector3 difference = this->position - position;
float distanceSquared = glm::dot(difference, difference);
if (distanceSquared == 0.0f)
{
return strength;
}
const float minimumStrength = 0.01f; // Pheromone strength epsilon
const float quadraticAttenuation = 1.0f; // Quadratic attenuation factor (1.0 = inverse-square falloff)
return strength / (1.0f + quadraticAttenuation * distanceSquared);
}

+ 71
- 0
src/game/pheromone.hpp View File

@ -0,0 +1,71 @@
/*
* Copyright (C) 2017 Christopher J. Howard
*
* This file is part of Antkeeper Source Code.
*
* Antkeeper Source Code is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Antkeeper Source Code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Antkeeper Source Code. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef PHEROMONE_HPP
#define PHEROMONE_HPP
#include <emergent/emergent.hpp>
using namespace Emergent;
class Pheromone
{
public:
void setPosition(const Vector3& position);
void setStrength(float strength);
const Vector3& getPosition() const;
float getStrength() const;
float getRadius() const;
float getRadiusSquared() const;
float getAttenuatedStrength(const Vector3& position) const;
private:
Vector3 position;
float strength;
float radius;
float radiusSquared;
};
inline void Pheromone::setPosition(const Vector3& position)
{
this->position = position;
}
inline const Vector3& Pheromone::getPosition() const
{
return position;
}
inline float Pheromone::getStrength() const
{
return strength;
}
inline float Pheromone::getRadius() const
{
return radius;
}
inline float Pheromone::getRadiusSquared() const
{
return radiusSquared;
}
#endif // PHEROMONE_HPP

+ 2
- 2
src/states/splash-state.cpp View File

@ -68,7 +68,7 @@ void SplashState::enter()
application->textureLoader->setCubemap(false);
application->textureLoader->setMipmapChain(false);
application->textureLoader->setMaxAnisotropy(1.0f);
application->splashTexture = application->textureLoader->load("data/textures/galileo_cross.hdr");
application->splashTexture = application->textureLoader->load("data/textures/splash.png");
application->titleTexture = application->textureLoader->load("data/textures/title.png");
// Get UI strings
@ -493,7 +493,7 @@ void SplashState::enter()
// Models
application->displayModel = application->modelLoader->load("data/models/icosphere.mdl");
application->antModel = application->modelLoader->load("data/models/agent.mdl");
application->antModel = application->modelLoader->load("data/models/debug-worker.mdl");
// Model instances
application->displayModelInstance = new ModelInstance();

+ 44
- 31
src/states/title-state.cpp View File

@ -46,26 +46,6 @@ void TitleState::enter()
// Setup screen fade-in transition
fadeIn = false;
fadeOut = false;
/*
// Load tunnel texture
GLuint tunnelTexture;
loadTexture("data/textures/soil-01.png", &tunnelTexture);
// Setup triplanar texturing
Material* material = (Material*)application->displayModel->getMaterial(0);
material->setRoughness(0.75f);
material->setDiffuseColor(glm::vec3(1.0f));
material->setSpecularColor(glm::vec3(0.001f));
material->setOpacity(0.999f);
Texture* texture = material->createTexture();
texture->setTextureID(tunnelTexture);
texture->setCoordinateSource(TextureCoordinateSource::TRIPLANAR_PROJECTION);
texture->setCoordinateScale(glm::vec3(1.0f / 2.0f));
texture->setDiffuseInfluence(1.0f);
*/
application->displayModelInstance->setModel(application->displayModel);
application->displayModelInstance->setTransform(Transform::getIdentity());
@ -73,6 +53,29 @@ void TitleState::enter()
application->antModelInstance->setModel(application->antModel);
application->antModelInstance->setTransform(Transform::getIdentity());
// BG
application->bgBatch.resize(1);
BillboardBatch::Range* bgRange = application->bgBatch.addRange();
bgRange->start = 0;
bgRange->length = 1;
Billboard* bgBillboard = application->bgBatch.getBillboard(0);
bgBillboard->setDimensions(Vector2(1.0f, 1.0f));
bgBillboard->setTranslation(Vector3(0.5f, 0.5f, 0.0f));
bgBillboard->setTintColor(Vector4(1, 0, 0, 1));
application->bgBatch.update();
application->vignettePass.setRenderTarget(&application->defaultRenderTarget);
application->bgCompositor.addPass(&application->vignettePass);
application->bgCompositor.load(nullptr);
application->bgCamera.setOrthographic(0, 1.0f, 1.0f, 0, -1.0f, 1.0f);
application->bgCamera.lookAt(glm::vec3(0), glm::vec3(0, 0, -1), glm::vec3(0, 1, 0));
application->bgCamera.setCompositor(&application->bgCompositor);
application->bgCamera.setCompositeIndex(0);
application->bgScene.addLayer();
application->bgScene.getLayer(0)->addObject(&application->bgCamera);
application->bgScene.getLayer(0)->addObject(&application->bgBatch);
// Setup lighting
application->sunlight.setColor(glm::vec3(1.0f));
application->sunlight.setDirection(glm::normalize(glm::vec3(0.5, -1, -0.5)));
@ -159,9 +162,16 @@ void TitleState::enter()
// Setup colony
colony.setAntModel(application->antModel);
for (int i = 0; i < 20; ++i)
for (int i = 0; i < 10; ++i)
{
ant = colony.spawn(&navmesh, (*navmesh.getTriangles())[0], normalize_barycentric(Vector3(0.5f)));
Navmesh::Triangle* triangle = (*navmesh.getTriangles())[0];
ant = colony.spawn(&navmesh, triangle, normalize_barycentric(Vector3(0.5f)));
Vector3 forward = glm::normalize(triangle->edge->vertex->position - triangle->edge->next->vertex->position);
Vector3 up = triangle->normal;
ant->setOrientation(forward, up);
application->scene.getLayer(0)->addObject(ant->getModelInstance());
ant->setState(Ant::State::WANDER);
}
@ -184,13 +194,6 @@ void TitleState::execute()
// Add dt to state time
stateTime += dt;
// Update menu controls
application->menuControlProfile->update();
application->gameControlProfile->update();
// Update input
application->inputManager->update();
if (substate == 0 || substate == 1)
{
if (stateTime >= titleDelay && !application->titleImage->isVisible())
@ -222,12 +225,12 @@ void TitleState::execute()
{
InputEvent event;
application->inputManager->listen(&event);
if (event.type != InputEvent::Type::NONE)
{
application->menuControlProfile->update();
application->inputManager->update();
// Check if application was closed
if (application->escape.isTriggered())
{
@ -278,6 +281,13 @@ void TitleState::execute()
}
}
// Update menu controls
application->menuControlProfile->update();
application->gameControlProfile->update();
// Update input
application->inputManager->update();
// Check state time
if (!fadeIn && stateTime >= blankDuration)
{
@ -405,6 +415,9 @@ void TitleState::execute()
glClearColor(0.0f, 0.0f, 0.0f, 1.0f);
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_STENCIL_BUFFER_BIT);
// Render BG
application->renderer.render(application->bgScene);
// Render scene
application->renderer.render(application->scene);

+ 1
- 0
src/states/title-state.hpp View File

@ -24,6 +24,7 @@
#include "../ui/ui.hpp"
#include "../game/ant.hpp"
#include "../game/colony.hpp"
#include <emergent/emergent.hpp>
using namespace Emergent;

+ 6
- 1
src/ui/ui.cpp View File

@ -374,11 +374,16 @@ void UIBatcher::batchImage(BillboardBatch* result, const UIImage* image)
// Get range
BillboardBatch::Range* range = getRange(result, image);
// Pixel-perfect
//Vector3 translation = Vector3((int)(image->getPosition().x + image->getDimensions().x * 0.5f), (int)(image->getPosition().y + image->getDimensions().y * 0.5f), image->getLayer() * 0.01f);
Vector3 translation = Vector3(image->getPosition() + image->getDimensions() * 0.5f, image->getLayer() * 0.01f);
// Create billboard
std::size_t index = range->start + range->length;
Billboard* billboard = result->getBillboard(index);
billboard->setDimensions(image->getDimensions());
billboard->setTranslation(Vector3(image->getPosition() + image->getDimensions() * 0.5f, image->getLayer() * 0.01f));
billboard->setTranslation(translation);
billboard->setTextureCoordinates(image->getTextureBounds().getMin(), image->getTextureBounds().getMax());
billboard->setTintColor(image->getColor());

Loading…
Cancel
Save