14 from twist_mux_msgs.msg
import JoyPriorityAction, JoyTurboAction
15 from geometry_msgs.msg
import Twist
16 from std_msgs.msg
import Bool
17 from visualization_msgs.msg
import Marker
23 def __init__(self, min_velocity, max_velocity, num_steps):
24 assert min_velocity > 0
and max_velocity > 0
and num_steps > 0
36 Takes a value in the range [0, 1] and the step and returns the
37 velocity (usually m/s or rad/s).
41 return value * max_value
45 def __init__(self, action_name, action_type, callback):
55 self.
_server.set_succeeded(result)
62 forward_min = rospy.get_param(
'~turbo/linear_forward_min', 1.0)
63 forward_max = rospy.get_param(
'~turbo/linear_forward_max', 1.0)
66 backward_min = rospy.get_param(
'~turbo/linear_backward_min', forward_min)
67 backward_max = rospy.get_param(
'~turbo/linear_backward_max', forward_max)
70 lateral_min = rospy.get_param(
'~turbo/linear_lateral_min', 1.0)
71 lateral_max = rospy.get_param(
'~turbo/linear_lateral_max', 1.0)
74 angular_min = rospy.get_param(
'~turbo/angular_min', 1.0)
75 angular_max = rospy.get_param(
'~turbo/angular_max', 1.0)
78 default_init_step = np.floor((self.
_num_steps + 1)/2.0)
79 init_step = rospy.get_param(
'~turbo/init_step', default_init_step)
80 if init_step < 0
or init_step > self.
_num_steps:
82 rospy.logwarn(
'Initial step %d outside range [1, %d]!'
83 ' Falling back to default %d' %
84 (init_step, self.
_num_steps, default_init_step))
90 if cmd.linear.z
or cmd.angular.x
or cmd.angular.y:
91 rospy.logerr(
"Joystick provided invalid values, only linear.x, linear.y and angular.z may be non-zero.")
93 if abs(cmd.linear.x) > 1.0
or abs(cmd.linear.y) > 1.0
or abs(cmd.angular.z) > 1.0:
94 rospy.logerr(
"Joystick provided invalid values (%d, %d, %d), not in [-1, 1] range." % (cmd.linear.x, cmd.linear.y, cmd.angular.z))
101 if cmd.linear.x >= 0:
134 self.
_pub = rospy.Publisher(
'text_marker', Marker, queue_size=1, latch=
True)
143 self.
_marker.type = Marker.TEXT_VIEW_FACING
145 self.
_marker.header.frame_id =
"base_footprint"
149 self.
_marker.pose.orientation.w = 1.0
158 def update(self, joystick_priority, add = True):
160 self.
_marker.action = Marker.ADD
162 self.
_marker.text =
"Manual" if joystick_priority
else "Autonomous"
164 self.
_marker.action = Marker.DELETE
176 self.
_pub_cmd = rospy.Publisher(
'joy_vel_out', Twist, queue_size=1)
179 self.
_pub_priority = rospy.Publisher(
'joy_priority', Bool, queue_size=1, latch=
True)
211 rospy.loginfo(
"Toggled joy_priority, current status is: %s", self.
_current_priority)
222 if __name__ ==
'__main__':
223 rospy.init_node(
'joystick_relay')