Skip to content

Commit 98d0832

Browse files
committed
Add ROS Action Server for recipe dispensing
1 parent a29a6ab commit 98d0832

4 files changed

+81
-8
lines changed

CMakeLists.txt

+13-8
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,10 @@ project(ratatouille_planner)
1010
find_package(catkin REQUIRED COMPONENTS
1111
roscpp
1212
rospy
13+
genmsg
1314
std_msgs
15+
actionlib_msgs
16+
actionlib
1417
)
1518

1619
## System dependencies are found with CMake's conventions
@@ -61,17 +64,19 @@ find_package(catkin REQUIRED COMPONENTS
6164
# )
6265

6366
## Generate actions in the 'action' folder
64-
# add_action_files(
65-
# FILES
66-
# Action1.action
67-
# Action2.action
68-
# )
67+
add_action_files(
68+
DIRECTORY
69+
action
70+
FILES
71+
RecipeRequest.action
72+
)
6973

7074
## Generate added messages and services with any dependencies listed here
71-
# generate_messages(
72-
# DEPENDENCIES
75+
generate_messages(
76+
DEPENDENCIES
7377
# std_msgs
74-
# )
78+
actionlib_msgs
79+
)
7580

7681
################################################
7782
## Declare ROS dynamic reconfigure parameters ##

action/RecipeRequest.action

+8
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# Goal
2+
uint32 recipe_id # specify which recipe to cook
3+
---
4+
# Result
5+
string status # OK or error message
6+
---
7+
# Feedback
8+
uint32 percent_complete

package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,8 @@
8080
<exec_depend>ar_track_alvar</exec_depend>
8181
<exec_depend>robotiq_urcap_control</exec_depend>
8282
<exec_depend>tf2_ros</exec_depend>
83+
<depend>actionlib</depend>
84+
<depend>actionlib_msgs</depend>
8385

8486

8587
<!-- The export tag contains other, unspecified, tags -->
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
#! /usr/bin/env python
2+
3+
import rospy
4+
5+
import actionlib
6+
7+
import ratatouille_planner.msg
8+
9+
10+
class RatatouilleAction(object):
11+
# create messages that are used to publish feedback/result
12+
_feedback = ratatouille_planner.msg.RecipeRequestFeedback()
13+
_result = ratatouille_planner.msg.RecipeRequestResult()
14+
15+
def __init__(self, name):
16+
self._action_name = name
17+
self._as = actionlib.SimpleActionServer(
18+
self._action_name,
19+
ratatouille_planner.msg.RecipeRequestAction,
20+
execute_cb=self.execute_cb,
21+
auto_start=False,
22+
)
23+
rospy.loginfo("Server started")
24+
self._as.start()
25+
26+
def execute_cb(self, goal):
27+
# helper variables
28+
r = rospy.Rate(1)
29+
success = True
30+
31+
# publish info to the console for the user
32+
rospy.loginfo("%s: Executing" % (self._action_name))
33+
34+
# start executing the action
35+
for i in range(1, 10):
36+
# check that preempt has not been requested by the client
37+
if self._as.is_preempt_requested():
38+
rospy.loginfo("%s: Preempted" % self._action_name)
39+
self._as.set_preempted()
40+
success = False
41+
break
42+
43+
self._feedback.percent_complete = i * 10
44+
# publish the feedback
45+
self._as.publish_feedback(self._feedback)
46+
# this step is not necessary, the sequence is computed at 1 Hz for demonstration purposes
47+
r.sleep()
48+
49+
if success:
50+
self._result.status = "OK"
51+
rospy.loginfo("%s: Succeeded" % self._action_name)
52+
self._as.set_succeeded(self._result)
53+
54+
55+
if __name__ == "__main__":
56+
rospy.init_node("RecipeRequest")
57+
server = RatatouilleAction(rospy.get_name())
58+
rospy.spin()

0 commit comments

Comments
 (0)