Skip to content

Commit

Permalink
Small cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
JosjaG committed Jun 18, 2021
1 parent a5bfcc1 commit d55ef54
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 14 deletions.
3 changes: 3 additions & 0 deletions launch/hero_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,9 @@
<remap from="odom" to="base/measurements" />
</node>

<!-- Joystick controller -->
<include file="$(find hero_bringup)/launch/tools/joy_teleop.launch" />

</group> <!-- End of TU/e namespace group -->

</launch>
10 changes: 2 additions & 8 deletions launch/tools/joy_teleop.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,8 @@
<?xml version="1.0"?>
<launch>

<arg name="namespace" default="/hero" />
<node name="joy_teleop" pkg="joy" type="joy_node" />

<group ns="$(arg namespace)">
<!-- <rosparam command="load" file="$(find hero_bringup)/parameters/tools/teleop.yaml" /> -->

<node name="joy_teleop" pkg="joy" type="joy_node" />

<node name="joy_controls" pkg="hero_bringup" type="joystick_controls_node" />
</group>
<node name="joy_controls" pkg="hero_bringup" type="joystick_controls_node" />

</launch>
7 changes: 1 addition & 6 deletions scripts/joystick_controls_node
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,9 @@ import sys

import rospy
import rosnode
import actionlib
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Twist
from sensor_msgs.msg import JointState
from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryActionGoal
from tue_manipulation_msgs.msg import GripperCommandAction, GripperCommandActionGoal
from robot_skills.get_robot import get_robot
from robot_skills.arm import arms

Expand All @@ -20,11 +17,9 @@ class JoystickControls(object):
Subscribes to the Joy messages sent via the controller and the joy node and then transforms these to the desired behavior
"""
self.controller_mode = 4
# self.map = self.controller_mappings[self.controller_mode]
self.controller_sub = rospy.Subscriber("joy", Joy, self.map_joystick, queue_size=1)
self.gripper_state_sub = rospy.Subscriber("joint_states", JointState, self.get_gripper_state, queue_size=1)

# Publish to kill all state_machines, to open/close the gripper, to move the base, loaded trajectory/pose, move the end effector
self.base_pub = rospy.Publisher("base/references", Twist, queue_size=1)
self.robot = get_robot('hero')
self.robot_arm = self.robot.get_arm(required_gripper_types=[arms.GripperTypes.GRASPING], required_goals=['show_gripper'])
Expand Down Expand Up @@ -67,7 +62,7 @@ class JoystickControls(object):
self.base_command = Twist()

def publish_controls(self):
self.base_pub.publish(self.base_command)
self.base_pub.publish(self.base_command)

def map_joystick(self, joy_msg):
controller_mappings = {4: {'A': joy_msg.buttons[0],
Expand Down

0 comments on commit d55ef54

Please sign in to comment.