39 from std_msgs.msg 
import Header, Int16, Float32
    40 from geometry_msgs.msg 
import Quaternion
    41 from cnn_bridge.msg 
import Detection
    45     '''A class to publish commands to ROS'''    48         '''Initialize ros publisher, ros subscriber'''    50             rospy.get_name() + 
'/' + topic_name, Detection, queue_size=1)
    53         """Set up a ROS camera    55             data  (str) The data to send to ROS [throttle, steer]    58             rosgraph.Master(
'/rostopic').getPid()
    60             raise rospy.ROSException(
"Unable to communicate with master!")
    62         detection = Detection()
    66         detection.classes = []
    67         for x 
in data[
'classes']:
    68             detection.classes.append(Int16(int(x)))
    70         for x 
in data[
'scores']:
    71             detection.scores.append(Float32(float(x)))
    73         for box 
in data[
'boxes']:
    79             detection.boxes.append(quat)
    82         h.stamp = rospy.Time.now()
    85         detection.image_identifier = meta_header
    87         self.detect_pub.publish(detection)
 
def __init__(self, topic_name="detection")
def send_mask(self, data, meta_header)