Skip to content

Commit b99212a

Browse files
committed
リベース
1 parent bd72334 commit b99212a

File tree

1 file changed

+89
-42
lines changed

1 file changed

+89
-42
lines changed

crane_robot_receiver/src/robot_receiver_node.cpp

+89-42
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,16 @@
44
// license that can be found in the LICENSE file or at
55
// https://opensource.org/licenses/MIT.
66

7-
#include <atomic>
7+
//#include <arpa/inet.h>
8+
//#include <netinet/in.h>
9+
//#include <stdio.h>
10+
//#include <stdlib.h>
11+
//#include <string.h>
12+
//#include <sys/socket.h>
13+
//#include <sys/types.h>
14+
//#include <time.h>
15+
16+
//#include <atomic>
817
#include <boost/asio.hpp>
918
#include <boost/thread.hpp>
1019
#include <crane_msgs/msg/robot_feedback.hpp>
@@ -24,7 +33,7 @@ struct RobotInterfaceConfig
2433
auto makeConfig(uint8_t id) -> RobotInterfaceConfig
2534
{
2635
RobotInterfaceConfig config;
27-
config.ip = "224.5.20." + std::to_string(id + 100);
36+
config.ip = "224.5.20.10" + std::to_string(id);
2837
config.port = 50100 + id;
2938
return config;
3039
}
@@ -57,39 +66,43 @@ union FloatUnion {
5766
char b[4];
5867
};
5968

60-
struct RobotInterface
69+
class MulticastReceiver
6170
{
62-
explicit RobotInterface(const RobotInterfaceConfig & config)
63-
: socket(io_context, udp::endpoint(udp::v4(), config.port)), config(config)
64-
{
65-
open();
66-
}
67-
68-
~RobotInterface() { socket.close(); }
69-
70-
void open()
71+
public:
72+
MulticastReceiver(const std::string & host, const int port)
73+
: socket(io_service, boost::asio::ip::udp::v4()), buffer(2048)
7174
{
72-
socket.open(endpoint.protocol());
73-
socket.set_option(udp::socket::reuse_address(true));
74-
socket.bind(endpoint);
75-
76-
auto address = boost::asio::ip::make_address(config.ip);
77-
socket.set_option(boost::asio::ip::multicast::join_group(address));
75+
boost::asio::ip::address addr = boost::asio::ip::address::from_string(host);
76+
if (!addr.is_multicast()) {
77+
throw std::runtime_error("expected multicast address");
78+
}
7879

79-
socket.async_receive_from(
80-
boost::asio::buffer(buffer, max_length), sender_endpoint,
81-
std::bind(&RobotInterface::handle_receive, this, _1, _2));
80+
socket.set_option(boost::asio::socket_base::reuse_address(true));
81+
socket.set_option(boost::asio::ip::multicast::join_group(addr.to_v4()));
82+
socket.bind(boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(), port));
83+
socket.non_blocking(true);
8284
}
8385

84-
void handle_receive(const boost::system::error_code & error, [[maybe_unused]] size_t bytes)
86+
bool receive()
8587
{
86-
if (error) {
87-
return;
88+
if (socket.available()) {
89+
boost::system::error_code error;
90+
received_size = socket.receive(boost::asio::buffer(buffer), 0, error);
91+
if (error && error != boost::asio::error::message_size) {
92+
throw boost::system::system_error(error);
93+
return false;
94+
}
95+
return true;
96+
} else {
97+
return false;
8898
}
99+
}
89100

101+
void updateFeedback()
102+
{
90103
FloatUnion float_union;
91104
RobotInfoUnion robot_info_union;
92-
robot_info_union.data = robot_feedback.load();
105+
robot_info_union.data = robot_feedback;
93106

94107
// 0,1byte目は識別子みたいな感じ
95108
auto header = buffer[2];
@@ -189,44 +202,43 @@ struct RobotInterface
189202
default:
190203
break;
191204
}
192-
robot_feedback.store(robot_info_union.data);
205+
robot_feedback = robot_info_union.data;
193206
}
194207

195-
// この変数は非同期で読み書きするのでatomicにする
196-
std::atomic<RobotFeedback> robot_feedback;
197-
198-
boost::asio::io_context io_context;
208+
RobotFeedback getFeedback() { return robot_feedback; }
199209

200-
udp::socket socket;
210+
private:
211+
boost::asio::io_service io_service;
201212

202-
udp::endpoint sender_endpoint;
213+
boost::asio::ip::udp::socket socket;
203214

204-
enum { max_length = 1024 };
215+
std::vector<char> buffer;
205216

206-
char buffer[max_length]{};
217+
size_t received_size;
207218

208-
udp::endpoint endpoint;
209-
210-
const RobotInterfaceConfig config;
219+
RobotFeedback robot_feedback;
211220
};
212221

213222
class RobotReceiverNode : public rclcpp::Node
214223
{
215224
public:
216-
RobotReceiverNode(uint8_t robot_num = 6) : rclcpp::Node("robot_receiver_node")
225+
RobotReceiverNode(uint8_t robot_num = 10) : rclcpp::Node("robot_receiver_node")
217226
{
218227
publisher = create_publisher<crane_msgs::msg::RobotFeedbackArray>("/robot_feedback", 10);
219228

220229
for (int i = 0; i < robot_num; i++) {
221230
auto config = makeConfig(i);
222-
robot_interfaces.push_back(std::make_shared<RobotInterface>(config));
231+
receivers.push_back(std::make_shared<MulticastReceiver>(config.ip, config.port));
223232
}
224233

225234
using namespace std::chrono_literals;
226235
timer = create_wall_timer(10ms, [&]() {
227236
crane_msgs::msg::RobotFeedbackArray msg;
228-
for (auto & robot_interface : robot_interfaces) {
229-
auto robot_feedback = robot_interface->robot_feedback.load();
237+
for (auto & receiver : receivers) {
238+
if (receiver->receive()) {
239+
receiver->updateFeedback();
240+
}
241+
auto robot_feedback = receiver->getFeedback();
230242
crane_msgs::msg::RobotFeedback robot_feedback_msg;
231243
robot_feedback_msg.robot_id = robot_feedback.head[0];
232244
robot_feedback_msg.counter = robot_feedback.counter;
@@ -267,7 +279,7 @@ class RobotReceiverNode : public rclcpp::Node
267279

268280
rclcpp::TimerBase::SharedPtr timer;
269281

270-
std::vector<std::shared_ptr<RobotInterface>> robot_interfaces;
282+
std::vector<std::shared_ptr<MulticastReceiver>> receivers;
271283

272284
rclcpp::Publisher<crane_msgs::msg::RobotFeedbackArray>::SharedPtr publisher;
273285
};
@@ -281,5 +293,40 @@ int main(int argc, char * argv[])
281293
exe.add_node(node->get_node_base_interface());
282294
exe.spin();
283295
rclcpp::shutdown();
296+
// try {
297+
// boost::asio::io_service io_service;
298+
//
299+
// // ローカルホストの指定したポートでUDPソケットを開く
300+
// udp::socket socket(io_service);
301+
// auto listen_address = boost::asio::ip::address::from_string("224.5.20.100");
302+
// boost::asio::ip::udp::endpoint listen_endpoint(listen_address, 50100);
303+
//
304+
// socket.open(listen_endpoint.protocol());
305+
//
306+
// if (socket.is_open()) {
307+
// std::cout << "socket opened" << std::endl;
308+
// } else {
309+
// std::cout << "socket not opened" << std::endl;
310+
// }
311+
// socket.set_option(boost::asio::ip::udp::socket::reuse_address(true));
312+
// socket.bind(listen_endpoint);
313+
//
314+
// // Join the multicast group.
315+
// socket.set_option(boost::asio::ip::multicast::join_group(listen_address));
316+
//
317+
//
318+
// std::cout << "joined multicast group" << std::endl;
319+
//
320+
// for (;;) { // 無限ループでパケットを待ち受ける
321+
// char data[1024];
322+
// udp::endpoint sender_endpoint;
323+
// size_t length = socket.receive_from(boost::asio::buffer(data), sender_endpoint);
324+
//
325+
// std::cout << "Received packet: " << std::string(data, length) << std::endl;
326+
// }
327+
// } catch (std::exception & e) {
328+
// std::cerr << "Exception: " << e.what() << "\n";
329+
// }
330+
284331
return 0;
285332
}

0 commit comments

Comments
 (0)