moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
teleop.py
Go to the documentation of this file.
1# Software License Agreement (BSD License)
2#
3# Copyright (c) 2022, Peter David Fagan
4# All rights reserved.
5#
6# Redistribution and use in source and binary forms, with or without
7# modification, are permitted provided that the following conditions
8# are met:
9#
10# * Redistributions of source code must retain the above copyright
11# notice, this list of conditions and the following disclaimer.
12# * Redistributions in binary form must reproduce the above
13# copyright notice, this list of conditions and the following
14# disclaimer in the documentation and/or other materials provided
15# with the distribution.
16# * Neither the name of Willow Garage, Inc. nor the names of its
17# contributors may be used to endorse or promote products derived
18# from this software without specific prior written permission.
19#
20# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31# POSSIBILITY OF SUCH DAMAGE.
32#
33# Author: Peter David Fagan
34""" Definition of an abstract base class for device teleoperation. """
35
36import rclpy
37
38from abc import ABC, abstractmethod
39import threading
40from rclpy.node import Node
41
42# messages/services
43from geometry_msgs.msg import TwistStamped
44from sensor_msgs.msg import Joy
45from std_srvs.srv import Trigger
46
47
48class TeleopDevice(ABC, Node):
49 """
50 An abstract base class for a teleoperation device.
51
52 This class expects both the `publish_command` and `record` methods to be overridden by inheriting classes.
53 """
54
55 def __init__(self, node_name, device_name, device_config, ee_frame_name):
56 super().__init__(node_name=node_name)
57 self.device_name = device_name
58 self.device_config = device_config
59 self.ee_frame_name = ee_frame_name
60
61 # default subscriber and publisher setup
62 self.joy_subscriber = self.create_subscription(
63 Joy, "/joy", self.publish_commandpublish_command, 10
64 )
65 self.twist_publisher = self.create_publisher(
66 TwistStamped, "/servo_node/delta_twist_cmds", 10
67 )
68 self.servo_node_start_client = self.create_client(
69 Trigger, "/servo_node/start_servo"
70 )
71 self.servo_node_stop_client = self.create_client(
72 Trigger, "/servo_node/stop_servo"
73 )
74
75 self.teleop_thread = None # gets created when teleop starts
76
77 def start_teleop(self):
78 """
79 Starts servo client and teleop process.
80 """
81 try:
82 # start servo client
83 self.servo_node_start_client.wait_for_service(10.0)
84 self.servo_node_start_client.call_async(Trigger.Request())
85
86 # spin the teleop node
87 # use multithreaded because Servo has concurrent processes for moving the robot and avoiding collisions
88 ex = rclpy.executors.MultiThreadedExecutor()
89 ex.add_node(self)
90 self.teleop_thread = threading.Thread(target=ex.spin, daemon=True)
91 self.teleop_thread.start()
92 except Exception as e:
93 print(e)
94
95 def stop_teleop(self):
96 """
97 Stops servo client and teleop process.
98 """
99 try:
100 self.servo_node_stop_client.wait_for_service(10.0)
101 self.servo_node_stop_client.call_async(Trigger.Request())
102 self.teleop_thread.join()
103 except Exception as e:
104 print(e)
105
106 @abstractmethod
108 """
109 Publishes the teleop command.
110 """
111 pass
112
113 @abstractmethod
114 def record(self):
115 """
116 Records trajectory data.
117 """
118 pass
__init__(self, node_name, device_name, device_config, ee_frame_name)
Definition teleop.py:55
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)