Skip to content

Commit

Permalink
Merge pull request #397 from osrf/jessica/ball_shooter_teleop
Browse files Browse the repository at this point in the history
Enable shooting the ball with the joystick
  • Loading branch information
j-herman authored Nov 15, 2021
2 parents a5947de + 472f51a commit 43de960
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 0 deletions.
1 change: 1 addition & 0 deletions vrx_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ add_message_files(
add_service_files(
FILES
ColorSequence.srv
BallShooter.srv
)

# Python scripts setup
Expand Down
9 changes: 9 additions & 0 deletions vrx_gazebo/config/diffdrive.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -35,3 +35,12 @@ teleop:
- axis: 2
target: data
scale: -1.0

ball_shooter:
type: service
interface_type: vrx_gazebo/srv/BallShooter
service_name: /ball_shooter
service_request:
shoot: true
buttons: [6]

10 changes: 10 additions & 0 deletions vrx_gazebo/nodes/twist2thrust.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
import rospy
from geometry_msgs.msg import Twist
from std_msgs.msg import Float32
from vrx_gazebo.srv import BallShooter
from std_msgs.msg import Empty

class Node():
def __init__(self,linear_scaling,angular_scaling,keyboard=False):
Expand All @@ -15,6 +17,7 @@ def __init__(self,linear_scaling,angular_scaling,keyboard=False):
self.left_msg =None
self.right_msg =None
self.keyboard = keyboard
self.shooter_pub = None

def callback(self,data):
rospy.logdebug("RX: Twist "+rospy.get_caller_id())
Expand Down Expand Up @@ -45,6 +48,9 @@ def callback(self,data):
self.left_pub.publish(self.left_msg)
self.right_pub.publish(self.right_msg)

def handle_ball_shooter(self,req):
self.shooter_pub.publish()
return True

if __name__ == '__main__':

Expand All @@ -71,6 +77,10 @@ def callback(self,data):
# Subscriber
rospy.Subscriber("cmd_vel",Twist,node.callback)

# Service - adds functionality to shoot via joystick
sub = rospy.Service('ball_shooter', BallShooter, node.handle_ball_shooter)
node.shooter_pub = rospy.Publisher("/wamv/shooters/ball_shooter/fire", Empty,queue_size=1)

try:
rospy.spin()
except rospy.ROSInterruptException:
Expand Down
5 changes: 5 additions & 0 deletions vrx_gazebo/srv/BallShooter.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# Ball shooter service

bool shoot
---
bool success

0 comments on commit 43de960

Please sign in to comment.