#使用Action通信机制移动小海龟
1、创建工作包
lzw08@ubuntu:~$ cd ros_workspace/src
lzw08@ubuntu:~/ros_workspace/src$ catkin_create_pkg turtlemove roscpp rospy rosmsg std_msgs
说明:第一步是在工作空间下创建了一个名为 turtlemove 的工作包,roscpp、rospy、rosmsg、std_msgs都是此工作包的依赖项。
2、进入工作包创建action目录及.action文件
lzw08@ubuntu:~/ros_workspace/src$ cd turtlemove/
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ mkdir action
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ cd action/
lzw08@ubuntu:~/ros_workspace/src/turtlemove/action$ touch turtleMove.action
将以下代码粘贴到.action文件中:
# Define the goal
float64 turtle_target_x
float64 turtle_target_y
float64 turtle_target_theta
---
# Define the result
float64 turtle_final_x
float64 turtle_final_y
float64 turtle_final_theta
---
# Define a feedback message
float64 present_turtle_x
float64 present_turtle_y
float64 present_turtle_theta
然后保存并关闭。
说明:第二步是在新建的turtlemove工作包下新建了action目录,并且在action目录中新建了一个名为turtleMove.action的文件。
3、回到上级目录修改相关文件
1)修改package.xml
lzw08@ubuntu:~/ros_workspace/src/turtlemove/action$ cd ..
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ gedit package.xml
修改前:
修改后:
供复制:
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rosmsg</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rosmsg</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>message_generation</build_export_depend>
<build_export_depend>actionlib</build_export_depend>
<build_export_depend>actionlib_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rosmsg</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>message_generation</exec_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>
2)修改CMakeLists.txt
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ gedit CMakeLists.txt
修改前 vs 修改后
4、回到工作空间编译
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ cd ~/ros_workspace/
lzw08@ubuntu:~/ros_workspace$ catkin_make
注意观察工作空间下的devel目录下是否有include目录生成,里面包含的文件如下图:
5、进入工作包里面的src建.cpp文件
lzw08@ubuntu:~/ros_workspace$ cd src/turtlemove/src
lzw08@ubuntu:~/ros_workspace/src/turtlemove/src$ touch turtleMoveClient.cpp
lzw08@ubuntu:~/ros_workspace/src/turtlemove/src$ touch turtleMoveServer.cpp
1)turtleMoveClient.cpp
#include <actionlib/client/simple_action_client.h>
#include "turtlemove/turtleMoveAction.h"
#include <turtlesim/Pose.h>
#include <turtlesim/Spawn.h>
#include <geometry_msgs/Twist.h>
typedef actionlib::SimpleActionClient<turtlemove::turtleMoveAction> Client;
struct Myturtle
{
float x;
float y;
float theta;
}turtle_present_pose;
// 当action完成后会调⽤该回调函数⼀次
void doneCb(const actionlib::SimpleClientGoalState& state,
const turtlemove::turtleMoveResultConstPtr& result)
{
ROS_INFO("海⻳机器⼈移动已结束 finished ! action完成后");
ros::shutdown();
}
// 当action激活后会调⽤该回调函数⼀次
void activeCb()
{
ROS_INFO("Goal just went active");
}
// 收到feedback后调⽤该回调函数
void feedbackCb(const turtlemove::turtleMoveFeedbackConstPtr& feedback)
{
ROS_INFO(" 海⻳机器⼈的位置 Pose : %f %f %f", feedback->present_turtle_x,
feedback->present_turtle_y,feedback->present_turtle_theta);
}
int main(int argc, char** argv)
{ setlocale(LC_CTYPE, "zh_CN.utf8");
ros::init(argc, argv, "turtleMoveClient");
// 定义⼀个客⼾端
Client client("turtleMove", true);
// 等待服务器端
ROS_INFO("正在等待Action服务器启动.");
client.waitForServer();// 等待动作服务器启动
ROS_INFO("Action服务器已启动,正在发送⽬标.");
// 创建⼀个action的goal 声明动作⽬标
turtlemove::turtleMoveGoal goal;
goal.turtle_target_x = 8;
goal.turtle_target_y = 8;
goal.turtle_target_theta = 2;
// 发送action的goal给服务器端,并且设置回调函数
client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);// 发送动作⽬标
ros::spin();
return 0;
}
2)turtleMoveServer.cpp
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include "turtlemove/turtleMoveAction.h"
#include <turtlesim/Pose.h>
#include <turtlesim/Spawn.h>
#include <geometry_msgs/Twist.h>
typedef actionlib::SimpleActionServer<turtlemove::turtleMoveAction> Server;
struct Myturtle
{
float x;
float y;
float theta;
}turtle_original_pose,turtle_target_pose;
ros::Publisher turtle_vel;
void posecallback(const turtlesim::PoseConstPtr& msg)
{
//ROS_INFO("海⻳机器⼈的位置:(%f,%f,%f)",msg->x,msg->y,msg->theta);
turtle_original_pose.x=msg->x;
turtle_original_pose.y=msg->y;
turtle_original_pose.theta=msg->theta;
}
// 收到action的goal后调⽤该回调函数
void execute(const turtlemove::turtleMoveGoalConstPtr& goal, Server* as)
{
turtlemove::turtleMoveFeedback feedback;
ROS_INFO("海⻳机器⼈ 开始启动.");
turtle_target_pose.x=goal->turtle_target_x;
turtle_target_pose.y=goal->turtle_target_y;
turtle_target_pose.theta=goal->turtle_target_theta;
geometry_msgs::Twist vel_msgs;
float break_flag;
while(1)
{
ros::Rate r(1);
vel_msgs.angular.z = 1.0 * (atan2(turtle_target_pose.y-turtle_original_pose.y,
turtle_target_pose.x-turtle_original_pose.x)-
turtle_original_pose.theta);
vel_msgs.linear.x = 0.2 * sqrt(pow(turtle_target_pose.x-turtle_original_pose.x, 2) +
pow(turtle_target_pose.y-turtle_original_pose.y, 2));
break_flag=sqrt(pow(turtle_target_pose.x-turtle_original_pose.x, 2) +
pow(turtle_target_pose.y-turtle_original_pose.y, 2));
turtle_vel.publish(vel_msgs);
feedback.present_turtle_x=turtle_original_pose.x;
feedback.present_turtle_y=turtle_original_pose.y;
feedback.present_turtle_theta=turtle_original_pose.theta;
as->publishFeedback(feedback);
ROS_INFO("break_flag=%f",break_flag);
if(break_flag<0.1) break;
r.sleep();
}
// 当action完成后,向客⼾端返回结果
ROS_INFO("海⻳机器⼈移动已结束 server.");
as->setSucceeded();
}
int main(int argc, char** argv)
{ setlocale(LC_CTYPE, "zh_CN.utf8");
ros::init(argc, argv, "turtleMove");
ros::NodeHandle n,turtle_node;
ros::Subscriber sub = turtle_node.subscribe("turtle1/pose",10,&posecallback);
//订阅海⻳机器⼈的位置信息
turtle_vel = turtle_node.advertise<geometry_msgs::Twist>("turtle1/cmd_vel",2);
//发布控制海⻳机器⼈运动的速度
// 定义⼀个服务器
Server server(n, "turtleMove", boost::bind(&execute, _1, &server), false);
// 服务器开始运⾏
server.start();
ROS_INFO("服务器已启动.");
ros::spin();
return 0;
}
6、回到上级目录修改编译规则
lzw08@ubuntu:~/ros_workspace/src/turtlemove/src$ cd ..
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ gedit CMakeLists.txt
修改前 vs 修改后
add_executable(turtleMoveServer src/turtleMoveServer.cpp)
add_executable(turtleMoveClient src/turtleMoveClient.cpp)
target_link_libraries(turtleMoveServer
${catkin_LIBRARIES}
)
target_link_libraries(turtleMoveClient
${catkin_LIBRARIES}
)
7、回到工作空间编译
lzw08@ubuntu:~/ros_workspace/src/turtlemove$ cd ~/ros_workspace/
lzw08@ubuntu:~/ros_workspace$ catkin_make
编译成功就可以运行了。
8、运行
1)运行主节点
2)运行小海龟
3)运行turtleMoveClient节点
lzw08@ubuntu:~/ros_workspace$ source devel/setup.bash
lzw08@ubuntu:~/ros_workspace$ rosrun turtlemove turtleMoveClient
4)运行turtleMoveServer节点
lzw08@ubuntu:~$ cd ros_workspace/
lzw08@ubuntu:~/ros_workspace$ source devel/setup.bash
lzw08@ubuntu:~/ros_workspace$ rosrun turtlemove turtleMoveServer
上图也即最终效果图。
9、注意事项
1).action文件里面的代码全部得顶格,不然编译会出错!
2).cpp里面的头文件包含工作包名字,注意一致
还有其他问题可以在评论区留言或者私信我。