文章目录
- 自定义action
- 1. 定义action文件
- 2. 修改 package.xml
- 3. 修改 CMakeLists.txt
- 4. 运行 `catkin build`
- 5. simple_action_server.py
- 6. simple_action_client.py
- 测试
自定义action
ros 版本:kinetic
自定义test
包的文件结构如下
|-- test
| |-- CMakeLists.txt
| |-- action
| | `--Timer.action
| |-- package.xml
| |-- scripts
| | |-- simple_action_server.py
| | `-- simple_action_server.py
动作定义文件后缀 .action
。其组成和srv
非常相似。有关自定义srv
见链接。
1. 定义action文件
# the goal: to be sent by the client
duration time_to_wait
---# the result: to be sent by the server upon completion
duration time_elapsed
uint32 updates_sent
---# the feedback: to be sent periodically by the server during execution
duration time_elapsed
duration time_remaining
2. 修改 package.xml
向其中添加如下信息:
<build_depend>actionlib_msgs</build_depend><build_export_depend>actionlib_msgs</build_export_depend>
3. 修改 CMakeLists.txt
find_package(catkin REQUIRED COMPONENTSrospyroscppstd_msgsmessage_generationactionlib_msgs
)
## Generate actions in the 'action' folder
add_action_files(FILESTimer.action
)
## Generate added messages and services with any dependencies listed here
generate_messages(DEPENDENCIESactionlib_msgsstd_msgs # Or other packages containing msgs
)
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES testCATKIN_DEPENDS rospy message_runtime std_msgs roscpp actionlib_msgs
# DEPENDS system_lib
)
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
catkin_install_python(PROGRAMSscripts/simple_action_server.pyscripts/simple_action_client.pyDESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
4. 运行 catkin build
动作被正确编译后会生成6个msg
:TimerGoal.msg
, TimerResult.msg
, TimerFeedback.msg
, TimerActionFeedback.msg
, TimerActionGoal.msg
, TimerActionResult.msg
。
5. simple_action_server.py
#!/usr/bin/env pythonimport rospy
import time
import actionlib
from test.msg import TimerAction, TimerGoal, TimerResultdef do_timer(goal):start_time = time.time()time.sleep(goal.time_to_wait.to_sec())result = TimerResult()result.time_elapsed = rospy.Duration.from_sec(time.time() -start_time)result.updates_sent = 0server.set_succeeded(result)rospy.init_node("timer_action_server")
server = actionlib.SimpleActionServer("timer", TimerAction, do_timer, False) #记得写False
server.start()
rospy.spin()
chmod +x simple_action_server.py
6. simple_action_client.py
#!/usr/bin/env python
import rospyimport actionlib
from test.msg import TimerAction, TimerGoal, TimerResultrospy.init_node("timer_action_client")
client = actionlib.SimpleActionClient("timer", TimerAction)
client.wait_for_server()
goal = TimerGoal()
goal.time_to_wait = rospy.Duration.from_sec(5.0)
client.send_goal(goal)
client.wait_for_result()
print("Time elapsed: %f" % (client.get_result().time_elapsed.to_sec()))
chmod +x simple_action_client.py
测试
roscore
rosrun test simple_action_client.py
rosrun test simple_action_client.py
如下结果: