This file is indexed.

/usr/lib/python3/dist-packages/morse/middleware/ros/accelerometer.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
15
16
17
18
19
from geometry_msgs.msg import Twist
from morse.middleware.ros import ROSPublisher

class TwistPublisher(ROSPublisher):
    """ Publish the velocity of the acceleromter sensor.
    No angular information, only linear ones.
    """
    ros_class = Twist

    def default(self, ci='unused'):
        twist = Twist()
        twist.header = self.get_ros_header()

        # Fill twist-msg with the values from the sensor
        twist.linear.x = self.data['velocity'][0]
        twist.linear.y = self.data['velocity'][1]
        twist.linear.z = self.data['velocity'][2]

        self.publish(twist)