美文网首页
ROS action使用范例 rospy 版本

ROS action使用范例 rospy 版本

作者: book_02 | 来源:发表于2020-04-01 00:03 被阅读0次

action的基本用法,包括客户端与服务端的执行和反馈等。

首先保证ROS已经安装。

1. 创建 catkin 空间

mkdir -p catkin_ws/src
cd catkin_ws
catkin_make

此时如果出错,说明ROS没有正确安装。

2. 创建 package : action_demo

取包名为action_demo,并且创建必要的文件夹。

cd src
catkin_create_pkg action_demo roscpp rospy std_msgs

cd action_demo
mkdir src
mkdir action
mkdir scripts

3. 编辑 action_demo 内容 使用rospy

3.1 新建 DoDishes.action

创建 action_demo/action/DoDishes.action

# Define the goal
uint32 dishwasher_id  # Specify which dishwasher we want to use
---
# Define the result
uint32 total_dishes_cleaned
---
# Define a feedback message
float32 percent_complete

3.2 修改 CMakeLists.txt

以下是修改部分,可通过取消注释然后修改的方式来做

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  genmsg actionlib_msgs actionlib   #add
)


add_action_files(
    DIRECTORY action 
    FILES DoDishes.action
)

generate_messages(
  DEPENDENCIES
  std_msgs
  actionlib_msgs    # add
)

3.3 修改 package.xml

增加如下内容

<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>

上面是format2的,也可以写成下面的format1的,两种格式都可以

<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<run_depend>actionlib</run_depend> 
<run_depend>actionlib_msgs</run_depend>

3.4 返回 catkin_ws 编译

返回工作空间catkin_ws

然后 catkin_make ,看是否能够编译成功,如果报错,先解决错误,再往下走

3.5 新建 dishes_server.py

创建的脚本都放在 scripts 目录下

注意创建的脚本都要给写权限,才能被识别和执行

创建 action_demo/scripts/dishes_server.py

#! /usr/bin/env python

import roslib
roslib.load_manifest('action_demo')
import rospy
import actionlib

from action_demo.msg import DoDishesAction, DoDishesFeedback, DoDishesResult

class DoDishesServer:
    def __init__(self):
        self.server = actionlib.SimpleActionServer('do_dishes', DoDishesAction, self.execute, False)

        self.server.start()

    def execute(self, goal):
        rate = rospy.Rate(1) 
        feedback = DoDishesFeedback()

        rospy.loginfo("Dishwasher %d is working." % goal.dishwasher_id)
        
        for i in range(11):
            feedback.percent_complete = i * 10
            self.server.publish_feedback(feedback)
            rate.sleep()

        rospy.loginfo("Dishwasher %d finish working." % goal.dishwasher_id)

        result = DoDishesResult()
        result.total_dishes_cleaned = 10
        self.server.set_succeeded(result)


def server_action():
    rospy.init_node('do_dishes_server')
    server = DoDishesServer()
    rospy.spin()


if __name__=="__main__":
    server_action()

3.6 新建 dishes_client.py

创建 action_demo/scripts/dishes_client.py

#!/usr/bin/env python
# coding:utf-8

import roslib
roslib.load_manifest('action_demo')
import rospy
import actionlib

from action_demo.msg import DoDishesAction, DoDishesGoal

def done_cb(status, result):
    rospy.loginfo("Yay! The dishes(%d) are now clean" % result.total_dishes_cleaned)

def active_cb():
    rospy.loginfo("Goal just went active")

def feedback_cb(feedback):
    rospy.loginfo(" percent_complete : %f " % feedback.percent_complete)

def client_action():
    rospy.init_node('do_dishes_client')
    client = actionlib.SimpleActionClient('do_dishes', DoDishesAction)

    rospy.loginfo("Waiting for action server to start.")
    client.wait_for_server()
    rospy.loginfo("Action server started, sending goal.")

    goal = DoDishesGoal()
    goal.dishwasher_id = 1

    client.send_goal(goal, done_cb, active_cb, feedback_cb)

    client.wait_for_result()

    rospy.sleep(rospy.Duration(1))   


if __name__=="__main__":
    client_action()

给脚本写权限:
chmod +x action_demo/scripts/dishes_client.py
chmod +x action_demo/scripts/dishes_server.py

3.7 编译运行

返回工作空间 catkin_ws

catkin_make
看是否编译成功,如果有错误,要逐个去解决

刷新环境
source ~/catkin_ws/devel/setup.bash
rospack profile

在一个终端开启roscore
roscore

在一个终端开启server:
rosrun action_demo dishes_server.py

在一个终端开启client:
rosrun action_demo dishes_client.py

这样之后,就能看到信息输出

``

相关文章

网友评论

      本文标题:ROS action使用范例 rospy 版本

      本文链接:https://www.haomeiwen.com/subject/hxvnuhtx.html