diff --git a/fixposition_driver_lib/src/fixposition_driver.cpp b/fixposition_driver_lib/src/fixposition_driver.cpp index 95f634b..2d3c188 100644 --- a/fixposition_driver_lib/src/fixposition_driver.cpp +++ b/fixposition_driver_lib/src/fixposition_driver.cpp @@ -287,7 +287,11 @@ void FixpositionDriver::NovConvertAndPublish(const uint8_t* msg, int size) { } bool FixpositionDriver::CreateTCPSocket() { - struct sockaddr_in server_address; + if (client_fd_ != -1) { + std::cerr << "TCP connection already exists" << "\n"; + return true; + } + client_fd_ = socket(AF_INET, SOCK_STREAM, 0); if (client_fd_ < 0) { @@ -297,6 +301,7 @@ bool FixpositionDriver::CreateTCPSocket() { std::cout << "Client created.\n"; } + struct sockaddr_in server_address; server_address.sin_family = AF_INET; server_address.sin_addr.s_addr = INADDR_ANY; server_address.sin_port = htons(std::stoi(params_.fp_output.port)); @@ -312,6 +317,11 @@ bool FixpositionDriver::CreateTCPSocket() { } bool FixpositionDriver::CreateSerialConnection() { + if (client_fd_ != -1) { + std::cerr << "Serial connection already exists" << "\n"; + return true; + } + client_fd_ = open(params_.fp_output.port.c_str(), O_RDWR | O_NOCTTY); struct termios options; diff --git a/fixposition_driver_ros1/src/fixposition_driver_node.cpp b/fixposition_driver_ros1/src/fixposition_driver_node.cpp index 161426c..b5f3fb6 100644 --- a/fixposition_driver_ros1/src/fixposition_driver_node.cpp +++ b/fixposition_driver_ros1/src/fixposition_driver_node.cpp @@ -52,14 +52,13 @@ FixpositionDriverNode::FixpositionDriverNode(const FixpositionDriverParams& para odometry_enu0_pub_(nh_.advertise("/fixposition/odometry_enu", 100)), eul_pub_(nh_.advertise("/fixposition/ypr", 100)), eul_imu_pub_(nh_.advertise("/fixposition/imu_ypr", 100)) { - + ws_sub_ = nh_.subscribe(params_.customer_input.speed_topic, 100, &FixpositionDriverNode::WsCallback, this, ros::TransportHints().tcpNoDelay()); - - Connect(); + RegisterObservers(); } @@ -195,23 +194,23 @@ void FixpositionDriverNode::PublishNmea(NmeaMessage data) { if (data.checkEpoch()) { // Generate new message fixposition_driver_ros1::NMEA msg; - + // ROS Header msg.header.stamp = ros::Time::fromBoost(GpsTimeToPtime(data.gpzda.stamp)); msg.header.frame_id = "LLH"; - + // Latitude [degrees]. Positive is north of equator; negative is south msg.latitude = data.gpgga.latitude; - + // Longitude [degrees]. Positive is east of prime meridian; negative is west msg.longitude = data.gpgga.longitude; - + // Altitude [m]. Positive is above the WGS 84 ellipsoid msg.altitude = data.gpgga.altitude; // Speed over ground [m/s] msg.speed = data.gprmc.speed; - + // Course over ground [deg] msg.course = data.gprmc.course; @@ -224,7 +223,7 @@ void FixpositionDriverNode::PublishNmea(NmeaMessage data) { // Positioning system mode indicator, R (RTK fixed), F (RTK float), A (no RTK), E, N msg.mode = data.gprmc.mode; - + // Publish message nmea_pub_.publish(msg); }