ros action学习记录

1.创建action消息文件

    创建名为Fibonacci.action文件。对于.action文件来说,定义该action的目标,结果以及反馈的主题

    

#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence

在执行过程中会自动产生消息文件,同时要对CMakeList.txt文件进行修改

    1、将actionlib_msgs加入find_package的catkin模块中。

    

find_package(catkin REQUIRED COMPONENTS actionlib_msgs)

    2、使用add_action_files模块声明你想要建立的action


add_action_files(
  DIRECTORY action
  FILES Fibonacci.action
)

    3、使用generate_messages模块,声明消息的依赖项

generate_messages(
  DEPENDENCIES actionlib_msgs std_msgs  # Or other packages containing msgs
)

    4、将actionlib_msgs加入catkin_package模块

catkin_package(
  CATKIN_DEPENDS actionlib_msgs
)

    5、package.xml文件

加入依赖项

    

<exec_depend>message_generation</exec_depend>

建立完成之后,由创建的action文件可以自动长生msg文件,也会生成对应的头文件。同样可以看到结果。


同样可以手动通过action文件生成.msg文件。在终端输入

$ roscd actionlib_tutorials
$ rosrun actionlib_msgs genaction.py -o msg/ action/fibonacci.action

结果显示

Generating for action Averaging

2、编写一个简单的服务器

创建actionlib_tutorials/src/fibonacci_server.cpp

 
 
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <actionlib_tutorials/FibonacciAction.h>
class FibonacciAction
{
protected:
ros::NodeHandle nh_;
actionlib::SimpleActionServer < actionlib_tutorials::FibonacciAction > as_;
std::string action_name_;
actionlib_tutorials::FibonacciFeedback feedback_;
actionlib_tutorials::FibonacciResult result_;
//创建多个私有变量,节点实例化变量,actionlib实例化变量,保存反馈变量,保存结果变量
//创建行为的过程中,构建NodeHandle并传递到行为服务器中,如18行。在行为的构造函数中构造行为服务器
public:
FibonacciAction (std::string name) :
as_ (nh_, name, boost::bind ( & FibonacciAction::executeCB, this , _1), false ),
//类的成员函数不同于普通的函数,因为成员函数指针不能直接调用operator(),它必须被绑定到一个对象或指针,
//然后才能得到this指针进而调用成员函数。因此bind需要 “牺牲”一个占位符,要求提供一个类的实例、引用或者指针,通过对象作为第一个参数来调用成员函数
//this指针表示指向当前创建对象的指针,一般用于类成员函数的定义中,因为当前不知道具体是哪个对象(对象还没有建立),所以用this当建立对象时便指向该对象

action_name_ (name)
{
as_. start ();
}
//构造函数,并且初始化函数,创建action服务器,需要提供节点实例,action节点名称,所需的函数executeCB作为变量。
//executeCB实际是一个回调函数
//其中的boost::bind函数,是串联函数,其作用是将this,以及_1(代表第一个参数)这两个参数传入executeCB函数中
~FibonacciAction ( void )
{
}
void executeCB ( const actionlib_tutorials::FibonacciGoalConstPtr & goal)
//注意,这里传递的是boost的共享指针类型ConstPtr的goal作为参数
//boost::share_ptr是共享指针,是通过指针保持某个对象的共享拥有权的智能指针。即多个指针可以指向同一个对象,若干个shared_ptr对象可以拥有同一个对象。
//该指针对象通过维护一个引用计数,记录有多少个shared_ptr指针指向该对象,最后一个指向该对象的shared_ptr被销毁或重置时,即引用计数变为0时,该对象被销毁。调用对应的析构函数
{
ros::Rate r ( 1 );
bool success = true ;
feedback_. sequence . clear ();
feedback_. sequence . push_back ( 0 );
feedback_. sequence . push_back ( 1 );
//将seeds push_back入反馈定义的序列中
ROS_INFO ( "%s: Executing, creating fibonacci sequence of order %i with seeds %i,%i" ,
action_name_. c_str (),goal-> order ,feedback_. sequence [ 0 ],feedback_. sequence [ 1 ]);
//发布ROS_INFO来让用户指定行为正在运行
//一个行为服务器最主要的功能就是允许客户端请求取消当前的目标执行
//当一个客户端请求取消当前的目标时,行为服务器应当取消目标,并且执行重要的清理,并且调用setPreempted()
//该函数会发出当前行为已经被请求抢占的信号,并设置检查抢占请求服务器的等级到服务器系统
for ( int i = 1 ;i <= goal-> order ;i ++ )
{
if (as_. isPreemptRequested () || !ros::ok ())
{
ROS_INFO ( "%s:Preempted" ,action_name_. c_str ()); //action:抢占
as_. setPreempted ();
success = false ;
break ;
}
feedback_. sequence . push_back (feedback_. sequence [i] + feedback_. sequence [i - 1 ]);
//Fibonacci序列赋值给feedback变量,然后通过行为服务器提供的反馈通道发布出去,随后行为继续循环并发布反馈
as_. publishFeedback (feedback_);
//发布刚刚赋值后的feedback对象,然后进入新一轮循环
r. sleep ();
}
if (success)
{
result_. sequence = feedback_. sequence ;
ROS_INFO ( "%s:Succeeded" ,action_name_. c_str ());
as_. setSucceeded (result_);
}
}
};
int main ( int argc, char ** argv)
{
ros::init (argc, argv, "fibonacci" );
FibonacciAction fibonacci ( "fibonacci" );
ros::spin ();
return 0 ;
}

3、写一个简单的客户端

    建立名为fibonacci_client.cpp的文件

#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
//简单的行为客户端实现
#include <actionlib/client/terminal_state.h>
//目标可能的状态
#include <actionlib_tutorials/FibonacciAction.h>

int main ( int argc, char ** argv)
{
ros::init (argc, argv, "test_fibonacci" );

actionlib::SimpleActionClient < actionlib_tutorials::FibonacciAction > ac ( "fibonacci" , true );
//创建行为服务器
//成功后会开启客户端创建自己的线程
//参数1为action服务器的名称,参数2为bool值用于循环线程

ROS_INFO ( "Waiting for action server to start" );
ac. waitForServer ();

ROS_INFO ( "Action server started,sending goal" );
actionlib_tutorials::FibonacciGoal goal;
goal. order = 20 ;
ac. sendGoal (goal);
//定义action goal,填充order并发送

bool finished_before_timeout = ac. waitForResult ( ros::Duration ( 30.0 ));
//等待行为返回
if (finished_before_timeout) //如果目标在目标状态超时之前结束,就会报告
{
actionlib::SimpleClientGoalState state = ac. getState ();
ROS_INFO ( "Action finished %s" ,state. toString (). c_str ());
}
else
ROS_INFO ( "Action did not finish before time out" );
//否则会告知用户目标没有在指定时间内结束

return 0 ;
}


5、运行客户端和服务器

   rosrun actionlib_tutorials fibonacci_server

  rosrun actionlib_tutorials fibonacci_client

可以看到订阅信息

同样你可以使用rostopic list -v查看当前的主题订阅发布情况

也可以使用rqt_graph来查看图形界面

猜你喜欢

转载自blog.csdn.net/weixin_40609307/article/details/80928690
今日推荐