guest.cpp
/*
需求:编写客户端,发送两个整型变量作为请求数据,并处理响应结果。
步骤:
1.包含头文件;
2.初始化 ROS2 客户端;
3.定义节点类;
3-1.创建客户端;
3-2.等待服务连接;
3-3.组织请求数据并发送;
4.创建对象指针调用其功能,并处理响应;
5.释放资源。
*/
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "demo_msg/srv/key.hpp"
using demo_msg::srv::Key;
using namespace std::chrono_literals;
// 3.定义节点类;
class MinimalClient: public rclcpp::Node{
public:
MinimalClient():Node("minimal_client"){
// 3-1.创建客户端;
client = this->create_client<Key>("jet");
RCLCPP_INFO(this->get_logger(),"jet 客户端创建,等待连接服务端!");
}
// 3-2.等待服务连接;
bool connect_server(){
while (!client->wait_for_service(1s))
{
if (!rclcpp::ok())
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"强制退出!");
return false;
}
RCLCPP_INFO(this->get_logger(),"服务连接中,请稍候...");
}
return true;
}
// 3-3.组织请求数据并发送;
rclcpp::Client<Key>::FutureAndRequestId send_request(int64_t a, int64_t b){
auto request = std::make_shared<Key::Request>();
request->a = a;
request->b = b;
return client->async_send_request(request);
}
private:
rclcpp::Client<Key>::SharedPtr client;
};
bool rechange(int &sub1,int &sub2)
{
bool if_rechange =true;
if(sub1%3 !=0 || sub2%5 !=0)
{
if_rechange=false;
}
while(sub1%3 !=0)
{
sub1+=1;
}
while(sub2%5 !=0)
{
sub2+=1;
}
return if_rechange;
}
int main(int argc, char ** argv)
{
if (argc != 3){
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"请提交两个整型数据!");
return 1;
}
// 2.初始化 ROS2 客户端;
rclcpp::init(argc,argv);
// 4.创建对象指针并调用其功能;
auto client = std::make_shared<MinimalClient>();
bool flag = client->connect_server();
if (!flag)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"服务连接失败!");
return 0;
}
int sub1 = atoi(argv[1]);
int sub2 = atoi(argv[2]);
if(rechange(sub1,sub2))
{
RCLCPP_INFO(client->get_logger(),"符合条件,未更改");
}
else
{
RCLCPP_INFO(client->get_logger(),"不符合条件,已更改为%d,%d",sub1,sub2);
}
auto response = client->send_request(sub1,sub2);
// 处理响应
if (rclcpp::spin_until_future_complete(client,response) == rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_INFO(client->get_logger(),"请求正常处理");
RCLCPP_INFO(client->get_logger(),"响应结果:%ld!", response.get()->num);
} else {
RCLCPP_INFO(client->get_logger(),"请求异常");
}
// 5.释放资源。
rclcpp::shutdown();
return 0;
}
serve.cpp
/*
需求:编写服务端,接收客户端发送请求,提取其中两个整型数据,相加后将结果响应回客户端。
步骤:
1.包含头文件;
2.初始化 ROS2 客户端;
3.定义节点类;
3-1.创建服务端;
3-2.处理请求数据并响应结果。
4.调用spin函数,并传入节点对象指针;
5.释放资源。
*/
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "demo_msg/srv/key.hpp"
using demo_msg::srv::Key;
using std::placeholders::_1;
using std::placeholders::_2;
// 3.定义节点类;
class MinimalService: public rclcpp::Node{
public:
MinimalService():Node("minimal_service"){
// 3-1.创建服务端;
server = this->create_service<Key>("jet",std::bind(&MinimalService::add, this, _1, _2));
RCLCPP_INFO(this->get_logger(),"jet 服务端启动完毕,等待请求提交...");
}
private:
rclcpp::Service<Key>::SharedPtr server;
// 3-2.处理请求数据并响应结果。
void add(const Key::Request::SharedPtr req,const Key::Response::SharedPtr res){
res->num = req->a + req->b;
RCLCPP_INFO(this->get_logger(),"请求数据:(%ld,%ld),响应结果:%ld", req->a, req->b, res->num);
}
};
int main(int argc, char const *argv[])
{
// 2.初始化 ROS2 客户端;
rclcpp::init(argc,argv);
// 4.调用spin函数,并传入节点对象指针;
auto server = std::make_shared<MinimalService>();
rclcpp::spin(server);
// 5.释放资源。
rclcpp::shutdown();
return 0;
}
CmakeLists
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(demo_msg REQUIRED)
add_executable(guest src/guest.cpp)
ament_target_dependencies(
guest
"rclcpp"
"demo_msg"
)
add_executable(serve src/serve.cpp)
ament_target_dependencies(
serve
"rclcpp"
"demo_msg"
)
install(TARGETS
guest
serve
DESTINATION lib/${PROJECT_NAME})
ament_package()
package.xml
<depend>rclcpp</depend>
<depend>demo_msg</depend>
<depend>std_msgs</depend>
功能包:
demo_msg
Key.srv
int64 a
int64 b
---
int64 num
傻逼CSDN