This file is indexed.

/usr/lib/python3/dist-packages/morse/middleware/ros/motion_xyw.py is in python3-morse-simulator 1.4-2.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
import logging; logger = logging.getLogger("morse." + __name__)
from geometry_msgs.msg import Twist
from morse.middleware.ros import ROSSubscriber

class TwistReader(ROSSubscriber):
    """ Subscribe to a motion command and set ``x``, ``y`` and ``w`` local data. """
    ros_class = Twist

    def update(self, message):
        self.data["x"] = message.linear.x
        self.data["y"] = message.linear.y
        self.data["w"] = message.angular.z # yaw
        logger.debug("Executing x,y,omega movement: <%s, %s, %s>"%
                     (message.linear.x, message.linear.y, message.angular.z))