Class Auctioneer

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public std::enable_shared_from_this< Auctioneer >

Class Documentation

class Auctioneer : public std::enable_shared_from_this<Auctioneer>

The Auctioneer class is responsible for initiating and mediating the bidding process during task dispatching. Hence, this class instance is solely used within the Dispatcher class

Public Types

using BiddingResultCallback = std::function<void(const std::string &task_id, const std::optional<Response::Proposal> winner, const std::vector<std::string> &errors)>

Callback which will provide the winner when a bid is concluded

Param task_id:

[in] bidding task id

Param winner:

[in] single winner from all submissions. nullopt if non

using ConstEvaluatorPtr = std::shared_ptr<const Evaluator>

Public Functions

void request_bid(const BidNoticeMsg &bid_notice)

Start a bidding process by provide a bidding task. Note the each bidding process is conducted sequentially

Parameters:

bid_notice[in] bidding task, task which will call for bid

void ready_for_next_bid()

Call this to tell the auctioneer that it may begin to perform the next bid.

void set_evaluator(ConstEvaluatorPtr evaluator)

Provide a custom evaluator which will be used to choose the best bid If no selection is given, Default is: LeastFleetDiffCostEvaluator

Parameters:

evaluator[in]

Public Static Functions

static std::shared_ptr<Auctioneer> make(const std::shared_ptr<rclcpp::Node> &node, BiddingResultCallback result_callback, ConstEvaluatorPtr evaluator)

Create an instance of the Auctioneer. This instance will handle all the task dispatching bidding mechanism. A default evaluator is used.

See also

make()

Parameters:
  • node[in] ros2 node which will manage the bidding

  • result_callback[in] This callback fn will be called when a bidding result is concluded

class Evaluator

A pure abstract interface class for the auctioneer to choose the best choosing the best submissions.

Subclassed by rmf_task_ros2::bidding::LeastFleetCostEvaluator, rmf_task_ros2::bidding::LeastFleetDiffCostEvaluator, rmf_task_ros2::bidding::QuickestFinishEvaluator

Public Functions

virtual std::optional<std::size_t> choose(const Responses &responses) const = 0

Given a list of submissions, choose the one that is the “best”. It is up to the implementation of the Evaluator to decide how to rank.

virtual ~Evaluator() = default