紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
[ros2run]: Segmentation fault
-
系统ubuntu22.04,ros2
各位大佬,我在进行ROS2 RUN时,终端输出以下问题:ros2 run auv_socket imu_data_pub [INFO] [1679059271.449093718] [imu_data_pub]: Connect RUNNING [INFO] [1679059271.449619076] [imu_data_pub]: connected successfullly! server message: $AUXA,1873.105,001873.100, 0.000, 0.000, 0.000,31.88882479,120.56537209, 29.64, 0.000, 0.000,0.0000, 0.000464, 0.001863,-0.003287,-0.002777, 0.999490, 0.017888,23.31,31.88882479,120.56537209, 29.64, 0.000, 0.000, 0.000, 0,00|00|00|000|000|0.00,0x02004080,0x00000010*C9 ��U [ros2run]: Segmentation fault
我的惯导发布节点代码如下:
#include <memory> #include <iostream> #include <fstream> #include <iomanip> #include "rclcpp/rclcpp.hpp" #include <stdio.h> #include <stdlib.h> #include <string.h> #include <sys/socket.h> #include <sys/types.h> #include <unistd.h> #include <arpa/inet.h> #include <netinet/in.h> #include <fcntl.h> #include <sys/shm.h> #include "auv_msgs/msg/imu.hpp" // IMU数据传输发布 #define PORT 26 #define BUFSIZE 1024 // 23 DVL 26 IMU 29 USBL 32 BDS char *SERVER_IP = "192.168.0.7"; int result = 0; using namespace std; using namespace std::chrono_literals; class imu_data_pub : public rclcpp::Node { public: imu_data_pub() : Node("imu_data_pub") { // 添加上电信号的指令 auto now = std::chrono::system_clock::now(); // 通过不同精度获取相差的毫秒数 uint64_t dis_millseconds = std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()).count() - std::chrono::duration_cast<std::chrono::seconds>(now.time_since_epoch()).count() * 1000; time_t tt = std::chrono::system_clock::to_time_t(now); auto time_tm = localtime(&tt); char strTime[25] = {0}; sprintf(strTime, "%d-%02d-%02d %02d:%02d:%02d %03d", time_tm->tm_year + 1900, time_tm->tm_mon + 1, time_tm->tm_mday, time_tm->tm_hour, time_tm->tm_min, time_tm->tm_sec, (int)dis_millseconds); ofstream imufile; imufile.open("imudata.txt", ios::out | ios::app); imufile << "******" << strTime << "******" << endl; imufile.close(); // 创建发布对象 imu_publisher_ = this->create_publisher<auv_msgs::msg::IMU>("imu_data", 100); imu_timer_ = this->create_wall_timer(0.1s, std::bind(&imu_data_pub::imu_time_callback, this)); } private: void imu_time_callback() { // socket通讯 char recvbuf[BUFSIZE]; int socket_cli = socket(AF_INET, SOCK_STREAM, 0); if (socket_cli < 0) { RCLCPP_INFO(this->get_logger(), "socket() error!"); } struct sockaddr_in sev_addr; memset(&sev_addr, 0, sizeof(sev_addr)); sev_addr.sin_family = AF_INET; sev_addr.sin_port = htons(PORT); sev_addr.sin_addr.s_addr = inet_addr(SERVER_IP); RCLCPP_INFO(this->get_logger(), "Connect RUNNING"); if (connect(socket_cli, (struct sockaddr *)&sev_addr, sizeof(sev_addr)) < 0) { RCLCPP_INFO(this->get_logger(), "connect error"); } else { RCLCPP_INFO(this->get_logger(), "connected successfullly!"); } while (rclcpp::ok()) { // 读取变量信息 recv(socket_cli, recvbuf, sizeof(recvbuf), 0); printf("server message: %s\n", recvbuf); auto imu_data = auv_msgs::msg::IMU(); const char *split = ","; // 使用,割符进行分割 char *p = strtok(recvbuf, split); int num = 0; double imu_value[24]; while (p != NULL) { imu_value[num] = strtod(p, NULL); num++; p = strtok(NULL, split); } imu_data.header.frame_id = "imu_link"; rclcpp::Time imu_right_time = this->get_clock()->now(); imu_data.header.stamp = imu_right_time; imu_data.imu_run_time = imu_value[1]; imu_data.imu_utc_time = imu_value[2]; imu_data.imu_yaw = imu_value[3]; imu_data.imu_pitch = imu_value[4]; imu_data.imu_roll = imu_value[5]; imu_data.imu_lat = imu_value[6]; imu_data.imu_lon = imu_value[7]; imu_data.imu_height = imu_value[8]; imu_data.imu_n_velocity = imu_value[9]; imu_data.imu_e_velocity = imu_value[10]; imu_data.imu_estimate_err = imu_value[11]; imu_data.imu_x_angvel = imu_value[12]; imu_data.imu_y_angvel = imu_value[13]; imu_data.imu_z_angvel = imu_value[14]; imu_data.imu_x_speforce = imu_value[15]; imu_data.imu_y_speforce = imu_value[16]; imu_data.imu_z_speforce = imu_value[17]; imu_data.imu_sys_temp = imu_value[18]; imu_data.imu_ref_lat = imu_value[19]; imu_data.imu_ref_lon = imu_value[20]; imu_data.imu_ref_height = imu_value[21]; imu_data.imu_ref_northvel = imu_value[22]; imu_data.imu_ref_eastvel = imu_value[23]; imu_data.imu_ref_yaw = imu_value[24]; // 判断角度不能超过其规定范围 /*if (imu_data.imu_yaw < 0) { imu_data.imu_yaw += 360; // RCLCPP_INFO(this->get_logger(), "IMU DATA ERROR"); } else if (imu_data.imu_yaw > 360) { imu_data.imu_yaw -= 360; } else { */ // 将数据写入txt文件储存,以便后期调用 ofstream imufile; imufile.open("imudata.txt", ios::out | ios::app); for (int i = 0; i < 25; i++) { imufile << fixed << setprecision(4) << imu_value[i] << " "; } cout << endl; imufile.close(); // 发布数据 imu_publisher_->publish(imu_data); //} } close(socket_cli); } rclcpp::TimerBase::SharedPtr imu_timer_; rclcpp::Publisher<auv_msgs::msg::IMU>::SharedPtr imu_publisher_; }; int main(int argc, char *argv[]) { rclcpp::init(argc, argv); rclcpp::spin(std::make_shared<imu_data_pub>()); rclcpp::shutdown(); return 0; }
我利用的socket通信来获取数据信息,大佬们能帮我看看怎么回事吗,不胜感激
-
-
@yudonghou123 gdb一下看看