Skip to content

Instantly share code, notes, and snippets.

@tejashah88
Last active March 12, 2024 03:35
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save tejashah88/03f9a2d6517bcd1165494bcfa0d87cef to your computer and use it in GitHub Desktop.
Save tejashah88/03f9a2d6517bcd1165494bcfa0d87cef to your computer and use it in GitHub Desktop.

ROS 2 - Hello World Part 2 - Mouse Sensor

  1. Open a new terminal and source the workspace
cd ~/ros2_helloworld_ws
source install/local_setup.bash
  1. Create a new package
cd src
ros2 pkg create --build-type ament_python ros2_mouse_listener
  1. Install extra "system" dependencies
sudo apt install python3-pynput
  1. Create two files, one for the mouse sensor and one for the position blaster
cd ros2_mouse_listener
touch ros2_mouse_listener/mouse_node.py
touch ros2_mouse_listener/blaster_node.py
  1. Open VSCode within the working directory
code .
  1. In mouse_node.py, copy and paste the following template code. Fill out both functions below.
import rclpy
from rclpy.node import Node

from std_msgs.msg import Int32MultiArray

from pynput.mouse import Controller


class MouseSensorNode(Node):
    def __init__(self):
        super().__init__('mouse_sensor_node')
        # TODO: Implement publisher logic
        

    def publish_position(self):
        # TODO: Implement publishing logic
        pass


def main(args=None):
    rclpy.init(args=args)
    node = MouseSensorNode()
    rclpy.spin(node)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()
  1. In blaster_node.py, copy and paste the following template code. Fill out both functions below.
import rclpy
from rclpy.node import Node

from std_msgs.msg import Float32, Int32MultiArray


class BlasterNode(Node):
    def __init__(self):
        super().__init__('blaster_node')
        
        # TODO: Implement subscribing logic

    def on_mouse_reading(self, msg):
        # TODO: Implement callback
        pass


def main(args=None):
    rclpy.init(args=args)
    node = BlasterNode()
    rclpy.spin(node)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()
  1. Back to the terminal, make a launch file
mkdir launch
touch launch/launch.py
  1. Copy and paste the following into the launch.py
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package="ros2_mouse_listener",
            executable="mouse_sensor",
        ),
        Node(
            package="ros2_mouse_listener",
            executable="mouse_blaster",
        ),
    ])
  1. In ros2_mouse_listener/package.xml, add the following lines underneath <build_type>ament_python</build_type>
<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>ros2launch</exec_depend>

image

  1. In ros2_mouse_listener/setup.py, edit the following lines near entry_points.
entry_points={
        'console_scripts': [
                'mouse_sensor = ros2_mouse_listener.mouse_node:main',
                'mouse_blaster = ros2_mouse_listener.blaster_node:main',
        ],
},

image

  1. In ros2_mouse_listener/setup.py, edit the following lines. At the top of the file, add the following imports.
import os
from glob import glob

image

Near the data_files section, make it look like the following.

    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        
        # Include all launch files.
        (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*')))
    ],

image

Your final ros2_mouse_listener/setup.py should look like this.

import os
from glob import glob
from setuptools import find_packages, setup

package_name = 'ros2_mouse_listener'

setup(
    name=package_name,
    version='0.0.0',
    packages=find_packages(exclude=['test']),
    data_files=[
        ('share/ament_index/resource_index/packages',
            ['resource/' + package_name]),
        ('share/' + package_name, ['package.xml']),
        # Include all launch files.
        (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*')))
    ],
    install_requires=['setuptools'],
    zip_safe=True,
    maintainer='ros2',
    maintainer_email='ros2@todo.todo',
    description='TODO: Package description',
    license='TODO: License declaration',
    tests_require=['pytest'],
    entry_points={
        'console_scripts': [
                'mouse_sensor = ros2_mouse_listener.mouse_node:main',
                'mouse_blaster = ros2_mouse_listener.blaster_node:main',
        ],
    },
)
  1. Update the ROS package dependencies from your workspace
cd ~/ros2_helloworld_ws
rosdep install -i --from-path src --rosdistro humble -y
  1. Build your package
colcon build --packages-select ros2_mouse_listener

Method A - Running nodes individually

  1. In a brand new terminal window, run the following to start up the mouse sensor node
cd ~/ros2_helloworld_ws
source install/local_setup.bash
ros2 run ros2_mouse_listener mouse_sensor
  1. In a brand new terminal window, run the following to start up the mouse blaster node
cd ~/ros2_helloworld_ws
source install/local_setup.bash
ros2 run ros2_mouse_listener mouse_blaster

Method B - Running nodes all at once

In a brand new terminal window, run the following to start up both nodes at the same time

cd ~/ros2_helloworld_ws
source install/local_setup.bash
ros2 launch ros2_mouse_listener launch
@tejashah88
Copy link
Author

class MouseSensorNode(Node):
    def __init__(self):
        super().__init__('mouse_sensor_node')
        self.publisher = self.create_publisher(Int32MultiArray, 'mouse', 10)

        timer_period = 1 / 10
        self.timer = self.create_timer(timer_period, self.publish_position)

        self.mouse = Controller()
        

    def publish_position(self):
        msg = Int32MultiArray()
        mouse_position = self.mouse.position

        msg.data = mouse_position
        self.publisher.publish(msg)

@tejashah88
Copy link
Author

class BlasterNode(Node):
    def __init__(self):
        super().__init__('blaster_node')
        
        self.subscriber = self.create_subscription(Int32MultiArray, 'mouse', self.on_mouse_reading, 10)

    def on_mouse_reading(self, msg):
        mouse_pos = msg.data

        logger = self.get_logger()
        logger.debug(f'x = {mouse_pos[0]}, y = {mouse_pos[1]}')

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment