Class swarm_metrics_manager

Inheritance Relationships

Base Types

  • public rer::client< swarm_metrics_manager >

  • public rmetrics::fs_output_manager

Class Documentation

class swarm_metrics_manager : public rer::client<swarm_metrics_manager>, public rmetrics::fs_output_manager

Manager class for handling all of the metrics which can be generated by COSM on robots running ROS. Runs on the ROS master to gather metrics from all robots and write them out to the file system.

To transfer custom classes via ROS messages, you can’t have any std::atomic bits in the classes, because they aren’t copyable or movable, which is needed. But that’s OK because ROS (apparently) calls all subscribed callbacks serially rather than in threads, so there is no possibility of race conditions.

Public Functions

swarm_metrics_manager(const rmconfig::metrics_config *mconfig, const fs::path &root, size_t n_robots)
~swarm_metrics_manager(void) override = default
bool flush(const rmetrics::output_mode &mode, const rtypes::timestep&) override
void interval_reset(const rtypes::timestep&) override

We can’t reset metric collectors according to the current timestep, because we may receive packets from robots asynchronously. Instead, we maintain internal state and flush the ones that are ready each timestep.

Public Static Attributes

static constexpr const size_t kQueueBufferSize = 1000

Protected Functions

inline msg_tracking_map *msg_tracking(void)
void register_standard(const rmconfig::metrics_config *mconfig, size_t n_robots)

Register metrics collectors that do not require extra arguments.

  • cmspecs::spatial::kInterferenceCounts -> csmetrics::interference_metrics

  • cmspecs::blocks::kTransporter -> cfsm::metrics::block_transporter_metrics

  • cmspecs::blocks::kTransportee -> cfmetrics::block_transportee_metrics

  • cmspecs::blocks::kAcqCounts -> csmetrics::goal_acq_metrics

  • cmspecs::sensors::kBattery -> chsensors::metrics::battery_metrics

void register_with_n_block_clusters(const rmconfig::metrics_config *mconfig, size_t n_robots, size_t n_block_clusters)

Register metrics collectors that require the # of block clusters in the arena.

  • cmspecs::blocks::kClusters -> cfmetrics::block_cluster_metrics

void register_with_n_robots(const rmconfig::metrics_config *mconfig, size_t n_robots)

Register metrics collectors that need the # robots.

  • cmspecs::kinematics::kAvg -> ckin::metrics::kinematics_metrics

  • cmspecs::kinematics::kDist -> ckin::metrics::kinematics_metrics

bool wait_for_connection(const ::ros::Subscriber &sub)

After subscribing to a metric data topic, verify connection.