Class ScheduleDataNode

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class ScheduleDataNode : public rclcpp::Node

Public Types

using Element = rmf_traffic::schedule::Viewer::View::Element
using Negotiation = rmf_traffic_ros2::schedule::Negotiation

Public Functions

std::vector<Element> get_elements(const RequestParam &request_param) const

Query the schedule database for elements.

const std::unordered_set<uint64_t> get_conflict_ids() const

Get the ids of all participants that have active conflicts.

const std::vector<std::vector<uint64_t>> get_conflict_groups() const

Get the groups of participants ids that have active conflicts with each other.

const std::vector<Element> get_negotiation_trajectories(uint64_t conflict_version, const std::vector<uint64_t> &sequence) const

Get the elements submitted by participants during a negotiation.

rmf_traffic::Time now()

Get the current time.

std::mutex &get_mutex()

Get a mutable reference to the mutex used by the ScheduleDataNode.

std::shared_ptr<Negotiation> get_negotiation()

Get a shared pointer to the ROS 2 negotiation interface.

Public Static Functions

static std::shared_ptr<ScheduleDataNode> make(const std::string &node_name, rmf_traffic::Duration wait_time = std::chrono::seconds(10), const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Builder function which returns a pointer to ScheduleDataNode when the Mirror Manager is readied. A nullptr is returned if initialization fails.

Parameters:
  • node_name[in] The name of the node

  • wait_time[in] The waiting duration to discover the rmf_traffic_schedule node