Only released in EOL distros:  

swarm_functions: area_division | coverage_path | kinematics_exchanger | state_exchanger | target_monitor | task_allocation

Package Summary

A package that offers action servers for assigning tasks between cyber physical system (CPS).

  • Maintainer status: developed
  • Maintainer: Micha Sende <sende AT lakeside-labs DOT com>, Gianluca Prato <prato AT ismb DOT it>, Micha Sende <sende AT lakeside-labs DOT com>
  • Author:
  • License: Apache License 2.0
  • Source: git https://github.com/cpswarm/swarm_functions.git (branch: kinetic-devel)

The task allocation uses a market-inspired approach by running a single-round, single-item auction. The package offers two action servers that perform the auction, one that acts as auctioneer and one that acts as bidder. The auctioneer opens the auction for a specific duration in which interested bidders can place a single bid. After the timeout the winner, i.e., the bidder with the highest bid is announced.

Dependencies

This package depends on the following message definitions:

The communication between CPSs is based on the CPSwarm Communication Library.

The following packages of the sensing and actuation library are required:

  • *_pos_provider

Further required packages are:

Execution

To start the action servers, run the launch file

roslaunch task_allocation task_allocation.launch

which launches both action servers which listen for incoming requests.

The launch file can be configured with following parameters:

id (integer, default: 1)

  • The identifier (ID) of the CPS used for name spacing in simulation.

output (string, default: screen)

  • Whether to show the program output (screen) or to write it to a log file (log).

In the param subdirectory there is the parameter file task_allocation.yaml that allows to configure the behavior of the auction process.

Nodes

auction_action

The auction_action node offers the task_allocation_auction action server that acts as auctioneer in the task allocation auction. When the action is called, it opens an auction and announces the task with ID and location. It then waits a specific time for the bids of other CPS. Once the auction timeout expires, it broadcasts the ID of the winning CPS, i.e., the one with the highest bid, to which the task is assigned. If no CPS participated in the auction, the action server aborts the auction goal.

Action Goal

cmd/task_allocation_auction/goal (cpswarm_msgs/TaskAllocationGoal)
  • A goal to start an auction containing the universally unique ID (UUID) of the auctioneer together with the ID and the position of the task that is auctioned.

Action Result

cmd/task_allocation_auction/result (cpswarm_msgs/TaskAllocationResult)
  • The result of the auction contains the UUID of the winning CPS, together with ID and position of the task that has been auctioned.

Subscribed Topics

bridge/events/cps_selection (cpswarm_msgs/TaskAllocationEvent)

Published Topics

cps_selected (cpswarm_msgs/TaskAllocatedEvent)

Parameters

~loop_rate (real, default: 5.0)
  • The frequency in Hz at which to run the control loops.
~queue_size (integer, default: 10)
  • The size of the message queue used for publishing and subscribing to topics.
~timeout (real, default: 10.0)
  • The time in seconds to listen for incoming bids from other CPSs after the auction has been opened, i.e., auction duration.

bid_action

The bid_action node offers the task_allocation_bid action server that acts as bidder in the task allocation auction opened by another CPS. When the action is called, it computes a bid for the task based on its location. The bid value is inversely proportional to the distance between the CPS and the task. It publishes the bid and waits until the auction ends. If the CPS has won the auction, the action server goal succeeds, otherwise it is aborted.

Action Goal

cmd/task_allocation_bid/goal (cpswarm_msgs/TaskAllocationGoal)
  • A goal to compute a bid containing the universally unique ID (UUID) of the auctioneer together with the ID and the position of the task that is auctioned.

Action Result

cmd/task_allocation_bid/result (cpswarm_msgs/TaskAllocationResult)
  • The result of the auction contains ID and position of the task that has been auctioned.

Subscribed Topics

pos_provider/pose (geometry_msgs/PoseStamped)
  • The current position of the CPS.
bridge/uuid (swarmros/String) bridge/events/cps_selected (cpswarm_msgs/TaskAllocatedEvent)

Published Topics

cps_selection (cpswarm_msgs/TaskAllocationEvent)

Parameters

~loop_rate (real, default: 5.0)
  • The frequency in Hz at which to run the control loops.
~queue_size (integer, default: 10)
  • The size of the message queue used for publishing and subscribing to topics.

Acknowledgements

This work is supported by the European Commission through the CPSwarm H2020 project under grant no. 731946.

Wiki: task_allocation (last edited 2019-11-05 21:39:14 by MichaSende)