Bratmobile
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
B2BConfigurator Class Reference

B2BConfigurator is a class that extends the AttentiveConfigurator to eliminate the Task splitting in fixed sized steps but finds waypoints by propagating disturbances back in time and across branches of the transitionSystem. More...

#include <b2bconfigurator.h>

Inheritance diagram for B2BConfigurator:
Inheritance graph
[legend]
Collaboration diagram for B2BConfigurator:
Collaboration graph
[legend]

Classes

class  ClearVoyance
 Stores disturbance lookaheads for alternative DEFAULT tasks (where the disturbance is backpropagated) More...
 

Public Member Functions

 B2BConfigurator (Task &task)
 
- Public Member Functions inherited from AttentiveConfigurator
 AttentiveConfigurator (Task _task)
 
- Public Member Functions inherited from Configurator
 Configurator (Task _task)
 
virtual void init (Task _task=Task())
 Initialises configurator. More...
 
virtual bool Spawner ()
 Calls functions to explore the state space and extract a plan. More...
 
int getIteration ()
 
void addIteration (int i=1)
 
void assignDisturbanceToTask (const Disturbance &d, Task &t)
 
void dummy_vertex (vertexDescriptor src)
 
simResult simulate (Task t, b2World &w)
 Simulates this task, includes creating the robot object. More...
 
virtual float remainingSimulationTime (const Task *const t=NULL)
 
void estimate_current_vertex ()
 
void printPlan (std::vector< vertexDescriptor > *p=NULL)
 
std::pair< edgeDescriptor, bool > addVertex (const vertexDescriptor &src, vertexDescriptor &v1, Edge edge=Edge(), bool topDown=0)
 Add state to the cognitive map and set next state Task direction and options. More...
 
void start ()
 
void stop ()
 
void registerInterface (LIDAR_In *, Motor_Out *)
 
virtual void change_task ()
 changes tasks executing on the robot
 
void update_graph (TransitionSystem &g, const TrackingResult &tr)
 
float approximate_angle (float angle, Direction d, simResult::resultType outcome)
 Approximating angle to divisors of pi/2. More...
 
virtual void adjust_goal_expectation ()
 Uses tracking information to adjust the position of the goal relative to the robot.
 
std::pair< bool, Direction > getOppositeDirection (Direction d)
 
void adjust_simulated_task (const vertexDescriptor &v, Task &t)
 If Task. More...
 
void register_controller (Controller *controller)
 
Controllerget_controller ()
 
void register_tracker (Tracker *_tracker)
 registers and initialises the tracker to the goal
 
Trackerget_tracker () const
 
Motor_Outget_motor_interface ()
 
LIDAR_Inget_lidar_interface ()
 
void register_planner (Planner *_p)
 
void setSimulationStep (float f)
 
void register_logger (Logger *l)
 
void register_goalChanger (GoalChanger *gc)
 
bool areInterfacesSetUp (Configurator *c=NULL)
 
void assignBodyFeatures (Task &t, const BodyFeatures &bf)
 Assigns body features to the disturbance of a task (NOTE: affordance and validity of the disturbance will remain the same) More...
 
void assignDimensions (Task &t, float halfLength, float halfWidth)
 Assigns dimensions to the disturbance of a task (NOTE: pose, affordance and validity of the disturbance will remain the same) More...
 
void register_worldBuilder (WorldBuilder *wb)
 
b2Transform get_start (const Task *const t)
 
Direction get_direction (const Task *const t)
 

Protected Member Functions

bool closeVertex (std::set< vertexDescriptor > &closed, vertexDescriptor v) override
 Closes a vertex but the maximum out edges number for a default state to have is 5 instead of 3. More...
 
std::vector< vertexDescriptor > splitTask (vertexDescriptor v, Direction d, vertexDescriptor src=TransitionSystem::null_vertex()) override
 Doesn't split the task, just returns the vertex of the task at hand; if Task fails or it's currently executing, it returns the source vertex for the task aswell. More...
 
virtual void backtrack (std::vector< vertexDescriptor > &evaluation_q, std::vector< vertexDescriptor > &priority_q, std::set< vertexDescriptor > &closed, std::vector< vertexDescriptor > &plan_prov, vertexDescriptor module_src=MOVING_VERTEX, vertexDescriptor startRecycle=MOVING_VERTEX) override
 Same as AttentiveConfigurator::backtrack, but also adds vertex to priority queue if the vertex is in the clearvoyance. More...
 
bool attentionWindowOverlaps (const Disturbance &Di, const State &q, b2World &world, const Disturbance &focus)
 Returns true if attention window overlap with Di. More...
 
int visitedEdgeCount (const std::vector< edgeDescriptor > &es)
 Counts the number of visited edges. More...
 
int minimumEdgesForClearvoyance (Direction direction)
 
virtual Disturbance getDisturbance (TransitionSystem &g, vertexDescriptor v, b2World &world, const Direction &dir, const b2Transform &start) override
 Uses clearvoyance to get the disturbance for a vertex if needed. More...
 
template<typename P >
std::vector< Direction > transitionInHindsight (vertexDescriptor v, P predicate)
 Looks at the frontier to unlock transitions from a vertex. More...
 
virtual std::vector< vertexDescriptor > explorer (vertexDescriptor v, TransitionSystem &g, b2World &w) override
 Constructs transition system using a Box2D simulation combined with an A* graph expansion algorithm. More...
 
virtual simResult simulate (Task t, b2World &world, vertexDescriptor v0)
 
virtual Robot makeRobot (b2World &world, const b2Transform &start, const Disturbance &focus)
 Overload of makeRobot, uses a disturbance which may be the goal of the hindsight disturbance to make the sensor. More...
 
void addOptionsInHindsight (vertexDescriptor v, vertexDescriptor v0, vertexDescriptor v1, ClearVoyance &clearvoyance)
 If the frontier is a default state and its source is a turning task, it adds an additional default option in hindsight if the state crashed. More...
 
- Protected Member Functions inherited from AttentiveConfigurator
ExecutionInfo package_info (vertexDescriptor gv=TransitionSystem::null_vertex(), bool been=false)
 Package task/goal execution details into an Execution Info instance. More...
 
virtual bool propagateD (vertexDescriptor v1, vertexDescriptor v0, std::set< vertexDescriptor > *closed=NULL, StateMatcher::MATCH_TYPE match=StateMatcher::_FALSE)
 Propagate a disturbance backwards to all states representing the same task (max 1) More...
 
void planPriority (TransitionSystem &, vertexDescriptor)
 
void adjust_rw_task (const vertexDescriptor &, TransitionSystem &, Task *, const b2Transform &)
 
virtual VertexMatch findMatch (State s, Direction dir=Direction::UNDEFINED, StateMatcher::MATCH_TYPE match_type=StateMatcher::_TRUE, StateDifference *_sd=NULL, std::vector< VertexMatch > *other_matches=NULL)
 Searches transition System for a match to a state provided. Continuous states are matched, with the option to also match the discrete state (the direction) More...
 
void resetPhi ()
 Resets all vertices evaluation function phi to a default unitialised value of 10.
 
std::pair< edgeDescriptor, bool > add_vertex_now (const vertexDescriptor &src, vertexDescriptor &v1, Disturbance obs, Edge edge=Edge(), bool topDown=0)
 Adds state after discovering it in exploration. More...
 
std::pair< edgeDescriptor, bool > add_vertex_retro (vertexDescriptor &src, vertexDescriptor &v1, Edge edge=Edge(), bool topDown=0)
 Adds vertices retroactively (e.g. after a state is split) More...
 
std::vector< Direction > getExploredDirections (vertexDescriptor v, const std::vector< Direction > &directions)
 
virtual void removeExploredTransitions (vertexDescriptor v)
 
virtual void transitionMatrix (vertexDescriptor v, Direction d, vertexDescriptor src)
 
void applyTransitionMatrix (vertexDescriptor v0, Direction d, bool ended, vertexDescriptor src, std::vector< vertexDescriptor > &plan_prov)
 Sets permitted transitions out of a state, formally combines jump guard J and guard Psi. More...
 
void addToPriorityQueue (vertexDescriptor v, std::vector< vertexDescriptor > &queue, const std::set< vertexDescriptor > &closed)
 Adds vertexDescriptor to priority queue according to a custom heuristic. More...
 
void ts_cleanup ()
 
void shift_states (TransitionSystem &, const std::vector< vertexDescriptor > &, const b2Transform &)
 
vertexDescriptor get_explore_start (TransitionSystem &)
 
void pre_explore ()
 Prepares transitionsystem for exploration: clears all edges of q0 with states that aren't the current one and updates instantaneous state q0 (vertex 0) with info about the Task in execution.
 
void explore_plan (b2World &) override
 Explores and plan.
 
std::vector< Direction >::iterator get_next_option (vertexDescriptor v, vertexDescriptor src, std::vector< vertexDescriptor > full_plan)
 Returns an iterator to the next option representing a discrete Task transition. If v is in the plan, returns the next task in the plan. If this next task is successful, after that option has been simulated it returns iterator to vector end. If not, returns other options. More...
 
virtual bool recycle_plan (vertexDescriptor v, vertexDescriptor &v0, vertexDescriptor &task_start, StateMatcher::MATCH_TYPE &matchType, b2Transform &shift_start, b2Transform &sk_first_start, std::pair< edgeDescriptor, bool > &edge, std::vector< vertexDescriptor > &plan_prov, Direction t_get_direction)
 Assesses whether a previous plan can be recycled. More...
 
std::pair< State, Edgesimulation_setup (b2World &w, Task &t, vertexDescriptor v0, b2Transform shift, b2Transform &start, std::vector< Direction >v0_options)
 Sets up for simulation. More...
 
void reassign_direction (vertexDescriptor bestNext, Direction &direction)
 Reassigns direction as the direction of the bext task to expand next in explorer. More...
 
bool matchToSafe (VertexMatch &match, const std::vector< VertexMatch > &other_matches=std::vector< VertexMatch >())
 if the match is a crashed task More...
 
std::pair< edgeDescriptor, bool > setup_match_edge (VertexMatch &match, vertexDescriptor &v0, vertexDescriptor &v1, const Edge &k, Direction direction, bool changedMatch)
 Given a valid match, sets up the edge with the previous vertex Creates new edge if it doesn't exist, changes the match to a safe state and allow the edge to be used in planning. More...
 
virtual std::vector< vertexDescriptor > task_vertices (vertexDescriptor v, std::pair< bool, edgeDescriptor > *ep=NULL)
 Rerturns all the vertices making up a task. More...
 
vertexDescriptor getRecyclingStart (vertexDescriptor v, vertexDescriptor v1, vertexDescriptor taskStart)
 Returns the vertex from which to start recycling plan. More...
 
std::vector< edgeDescriptor > inEdges (vertexDescriptor v, Direction d=UNDEFINED)
 Returns a vector of all the in-edges of vertex. More...
 
std::pair< edgeDescriptor, bool > addEdgeRetrospectively (vertexDescriptor v, vertexDescriptor &v1, const State &s_tmp, std::pair< edgeDescriptor, bool > first_edge, Direction d, float linearSpeed)
 Adds edge retrospectively (used in split task) More...
 
void correctQueue (std::vector< vertexDescriptor > &queue, vertexDescriptor v, vertexDescriptor startRecycle, int planProvSize)
 Edits. More...
 
void adjustProbability (const edgeDescriptor &e)
 Adjusts the probability that a continuous state (edge target) will occur after taking a discrete state transition from the edge source. More...
 
void abandonPlan (std::vector< vertexDescriptor > &planProv, vertexDescriptor v0, vertexDescriptor v1)
 Clears plan vector, sets current task to change and clears current vertices. More...
 
virtual std::vector< Direction > partiallyExplorativeOptions (std::pair< bool, edgeDescriptor > ve)
 Assigns options to vertex which has in previous iteration been expanded. Assigns direction of successful current task, or direction of other tasks if unsuccessful. More...
 
virtual Robot makeRobot (b2World &w, const b2Transform &start)
 Makes the robot object in the world with the given start position and task. More...
 
void visitedDirectionsPushBack (vertexDescriptor v, std::vector< Direction > &visitedDirections, Direction direction)
 Pushes directions visited at this iteration (not using phi) to input vector. More...
 
virtual StateMatcher::MATCH_TYPE desiredMatch ()
 
void enforce_edge ()
 Used to make sure that there is always a connection between DUMMY/MOVING to the next in plan - useful in sudden changes of plans.
 
virtual bool shouldPartiallyExplore (const std::vector< edgeDescriptor > &oe, std::pair< bool, edgeDescriptor > ve)
 Psi guard: should only current task be simulated?
 
virtual bool canPropagate (vertexDescriptor v)
 propagates only if the previous vertex More...
 
virtual bool canReassignOutcome (vertexDescriptor v)
 
virtual float customSimulationStep (vertexDescriptor v=TransitionSystem::null_vertex())
 

Protected Attributes

class B2BConfigurator::ClearVoyance clearvoyance
 
- Protected Attributes inherited from AttentiveConfigurator
StateMatcher matcher
 
- Protected Attributes inherited from Configurator
int iteration =0
 
int simulatedTasks =0
 
Task currentTask
 
Controllertask_controller =NULL
 
Trackertracker =NULL
 
LIDAR_Inci =NULL
 
Motor_Outcontrol =NULL
 
Plannerplanner =NULL
 
Loggerlogger =NULL
 
bool running =0
 
std::thread * LIDAR_thread =NULL
 
float simulationStep =2*std::max(ROBOT_HALFLENGTH, ROBOT_HALFWIDTH)
 
std::chrono::high_resolution_clock::time_point previousTimeScan
 
GoalChangergoal_changer =NULL
 
std::vector< vertexDescriptor > m_plan
 
std::vector< vertexDescriptor > current_vertices
 
Task controlGoal
 
CoordinateContainer data2fp
 
TransitionSystem transitionSystem =TransitionSystem(1)
 
WorldBuilderworldBuilder =new WorldBuilder()
 
vertexDescriptor currentVertex =MOVING_VERTEX
 
edgeDescriptor movingEdge =edgeDescriptor()
 
edgeDescriptor currentEdge =movingEdge
 

Additional Inherited Members

- Static Public Member Functions inherited from Configurator
static void run (Configurator *)
 Spawns tasks, creates plans, tracks task and controls real-world task switching option to run in thread. Thread can be used if planning time might exceed 200ms (LIDAR sampling rate) but doesn't have to be.
 
static void MulT (const b2Transform &B, Task &task)
 Matrix multiply by transpose.
 
static void InvMul (const b2Transform &B, Task &task)
 Matrix multiply by transpose.
 
static void InvMul_ (const b2Transform &B, Task &task)
 Matrix multiply by transpose.
 
static void Mul (const b2Transform &B, Task &task)
 Matrix multiplication.
 

Detailed Description

B2BConfigurator is a class that extends the AttentiveConfigurator to eliminate the Task splitting in fixed sized steps but finds waypoints by propagating disturbances back in time and across branches of the transitionSystem.

Member Function Documentation

◆ addOptionsInHindsight()

void B2BConfigurator::addOptionsInHindsight ( vertexDescriptor  v,
vertexDescriptor  v0,
vertexDescriptor  v1,
ClearVoyance clearvoyance 
)
protected

If the frontier is a default state and its source is a turning task, it adds an additional default option in hindsight if the state crashed.

Parameters
vsource vertex (options are added to this vertex in hindsight)
v0connecting vertex (has to be LEFT or RIGHT task for DEFAULT option to be added)
v1frontier state (has to be DEFAULT and crashed if option is to be added)
clearvoyance

◆ attentionWindowOverlaps()

bool B2BConfigurator::attentionWindowOverlaps ( const Disturbance Di,
const State q,
b2World &  world,
const Disturbance focus 
)
protected

Returns true if attention window overlap with Di.

Parameters
Diprevious state's Di
qprevious state
worldbox2d world
focusdisturbance to keep in focus to make the attetnion window (e.g. goal)

◆ backtrack()

void B2BConfigurator::backtrack ( std::vector< vertexDescriptor > &  evaluation_q,
std::vector< vertexDescriptor > &  priority_q,
std::set< vertexDescriptor > &  closed,
std::vector< vertexDescriptor > &  plan_prov,
vertexDescriptor  module_src = MOVING_VERTEX,
vertexDescriptor  startRecycle = MOVING_VERTEX 
)
overrideprotectedvirtual

Same as AttentiveConfigurator::backtrack, but also adds vertex to priority queue if the vertex is in the clearvoyance.

Parameters
evaluation_q
priority_q
closed
plan_prov
module_src
startRecycle

Reimplemented from AttentiveConfigurator.

◆ closeVertex()

bool B2BConfigurator::closeVertex ( std::set< vertexDescriptor > &  closed,
vertexDescriptor  v 
)
overrideprotectedvirtual

Closes a vertex but the maximum out edges number for a default state to have is 5 instead of 3.

Parameters
closed
v

Reimplemented from AttentiveConfigurator.

◆ explorer()

std::vector< vertexDescriptor > B2BConfigurator::explorer ( vertexDescriptor  v,
TransitionSystem &  g,
b2World &  w 
)
overrideprotectedvirtual

Constructs transition system using a Box2D simulation combined with an A* graph expansion algorithm.

Parameters
vstarting vertex
gthe transition system
wbox2d world
Returns
std::vector<vertexDescriptor> a plan, if recycled from previous knowledge

Reimplemented from AttentiveConfigurator.

◆ getDisturbance()

Disturbance B2BConfigurator::getDisturbance ( TransitionSystem &  g,
vertexDescriptor  v,
b2World &  world,
const Direction &  dir,
const b2Transform &  start 
)
overrideprotectedvirtual

Uses clearvoyance to get the disturbance for a vertex if needed.

Parameters
g
v
world
dir
start
Returns
Disturbance

Reimplemented from AttentiveConfigurator.

◆ makeRobot()

Robot B2BConfigurator::makeRobot ( b2World &  world,
const b2Transform &  start,
const Disturbance focus 
)
protectedvirtual

Overload of makeRobot, uses a disturbance which may be the goal of the hindsight disturbance to make the sensor.

Parameters
t
world
focusdisturbance focus of attention (used for making the sensor)
Returns
Robot

◆ splitTask()

std::vector< vertexDescriptor > B2BConfigurator::splitTask ( vertexDescriptor  v,
Direction  d,
vertexDescriptor  src = TransitionSystem::null_vertex() 
)
overrideprotectedvirtual

Doesn't split the task, just returns the vertex of the task at hand; if Task fails or it's currently executing, it returns the source vertex for the task aswell.

Parameters
vvertex of the task
ddirection of the task that are allowed to split (not used)
srcsource of the task
Returns
std::vector <vertexDescriptor>

//&& sameIterationEdgeIt!=ie.end()

Reimplemented from AttentiveConfigurator.

◆ transitionInHindsight()

template<typename P >
std::vector<Direction> B2BConfigurator::transitionInHindsight ( vertexDescriptor  v,
predicate 
)
inlineprotected

Looks at the frontier to unlock transitions from a vertex.

Template Parameters
Ppredicate
Parameters
vthe vertex
predicatethe assignment criteria if the frontier has less than 2 vertices
Returns
std::vector <Direction>

◆ visitedEdgeCount()

int B2BConfigurator::visitedEdgeCount ( const std::vector< edgeDescriptor > &  es)
protected

Counts the number of visited edges.

Parameters
esthe edges
Returns
int

The documentation for this class was generated from the following files: