in robot_ws/src/cloudwatch_robot/nodes/monitor_distance_to_goal.py [0:0]
def report_metric(self, msg):
if not msg.poses:
rospy.logdebug('Path empty, not calculating distance')
return
distance = self.calc_path_distance(msg)
rospy.logdebug('Distance to goal: %s', distance)
header = Header()
header.stamp = rospy.Time.from_sec(time.time())
dimensions = [
MetricDimension(name='robot_id', value='Turtlebot3'),
MetricDimension(name='category', value='RobotOperations'),
]
metric = MetricData(
header=header,
metric_name='distance_to_goal',
unit=MetricData.UNIT_NONE,
value=distance,
time_stamp=rospy.Time.from_sec(time.time()),
dimensions=dimensions,
)
self.metrics_pub.publish(MetricList([metric]))