Skip to content

Commit bee1dba

Browse files
V1.0.36 support multicast
1 parent 5db8f62 commit bee1dba

File tree

8 files changed

+46
-9
lines changed

8 files changed

+46
-9
lines changed

README.md

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,7 @@ $ roslaunch pandar_pointcloud transform_nodelet.launch data_type:=rosbag
138138
|---------|---------------|
139139
|calibration|Path of correction file, will be used when not able to get correction file from a connected Liar|
140140
|device_ip_ip|The IP address of connected Lidar, will be used to get correction file|
141+
|host_ip|The IP address of host pc, will be used to get udp data from lidar|
141142
|frame_id|frame id of published messages|
142143
|firetime_file|Path of firetime files|
143144
|pcap|Path of the pcap file, once not empty, driver will get data from pcap file instead of a connected Lidar|
@@ -149,4 +150,5 @@ $ roslaunch pandar_pointcloud transform_nodelet.launch data_type:=rosbag
149150
|channel_config_file|Path of channel config file, will be used when not able to get channel config file from a connected Liar|
150151
|cert_file|Path of the user's certificate|
151152
|private_key_file|Path of the user's private key|
152-
|ca_file|Path of the root certificate|
153+
|ca_file|Path of the root certificate|
154+
|multicast_ip|The multicast IP address of connected Lidar, will be used to get udp packets from multicast ip address|

change notes.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -139,5 +139,12 @@ PandarSwiftROS_1.0.31
139139
1. Fix bug in publish points mode
140140
2. Support 0x3a and 0x3e return mode of QT128
141141

142+
Monday December 5th, 2022 17:30
143+
##version
144+
PandarSwiftROS_1.0.36
145+
146+
##modify
147+
1. Support multicast
148+
142149

143150

pandar_pointcloud/include/pandar_pointcloud/input.h

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -123,8 +123,8 @@ typedef struct PandarPacket_s {
123123

124124
namespace pandar_pointcloud
125125
{
126-
static uint16_t DATA_PORT_NUMBER = 8080; // default data port
127-
static uint16_t POSITION_PORT_NUMBER = 8308; // default position port
126+
static uint16_t DATA_PORT_NUMBER = 2368; // default data port
127+
static uint16_t GPS_PORT_NUMBER = 8308; // default position port
128128

129129
#define PANDAR128_SEQUENCE_NUMBER_OFFSET (831)
130130
/** @brief pandar input base class */
@@ -164,7 +164,9 @@ namespace pandar_pointcloud
164164
{
165165
public:
166166
InputSocket(ros::NodeHandle private_nh,
167-
uint16_t port = DATA_PORT_NUMBER);
167+
std::string host_ip = "",
168+
uint16_t port = DATA_PORT_NUMBER,
169+
uint16_t gpsport = GPS_PORT_NUMBER, std::string multicast_ip = "");
168170
virtual ~InputSocket();
169171

170172
virtual int getPacket(PandarPacket *pkt);

pandar_pointcloud/launch/PandarSwift_points.launch

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
<!-- declare arguments with default values -->
77
<arg name="calibration" default="$(find pandar_pointcloud)/params/Pandar128_Correction.csv"/>
88
<arg name="device_ip" default="192.168.1.201" />
9+
<arg name="host_ip" default="" />
910
<arg name="frame_id" default="PandarSwift" />
1011
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
1112
<arg name="max_range" default="130.0" />
@@ -20,6 +21,7 @@
2021
<arg name="start_angle" default="0.0" />
2122
<arg name="publish_model" default="both_point_raw" />
2223
<arg name="namespace" default="hesai"/>
24+
<arg name="multicast_ip" default="239.0.0.2"/>
2325
<arg name="coordinate_correction_flag" default="false" />
2426
<arg name="channel_config_file" default="$(find pandar_pointcloud)/params/QT128C2X_Channel_Cofig.csv" />
2527
<!--"cert_file" represents the path of the user's certificate-->
@@ -40,6 +42,7 @@
4042
<arg name="min_range" value="$(arg min_range)"/>
4143
<arg name="start_angle" value="$(arg start_angle)"/>
4244
<arg name="device_ip" value="$(arg device_ip)" />
45+
<arg name="host_ip" value="$(arg host_ip)" />
4346
<arg name="frame_id" value="$(arg frame_id)"/>
4447
<arg name="publish_model" value="$(arg publish_model)"/>
4548
<arg name="pcap" value="$(arg pcap)"/>
@@ -50,6 +53,7 @@
5053
<arg name="rpm" value="$(arg rpm)"/>
5154
<arg name="firetime_file" value="$(arg firetime_file)"/>
5255
<arg name="namespace" value="$(arg namespace)"/>
56+
<arg name="multicast_ip" value="$(arg multicast_ip)"/>
5357
<arg name="coordinate_correction_flag" value="$(arg coordinate_correction_flag)"/>
5458
<arg name="channel_config_file" value="$(arg channel_config_file)"/>
5559
<arg name="cert_file" value="$(arg cert_file)" />

pandar_pointcloud/launch/cloud_nodelet.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<arg name="start_angle" default="0" />
99

1010
<arg name="device_ip" default="" />
11+
<arg name="host_ip" default="" />
1112
<arg name="frame_id" default="Pandar128" />
1213
<arg name="publish_model" default="both_point_raw" />
1314
<arg name="pcap" default="" />
@@ -33,6 +34,7 @@
3334
<param name="start_angle" value="$(arg start_angle)"/>
3435

3536
<param name="device_ip" value="$(arg device_ip)" />
37+
<param name="host_ip" value="$(arg host_ip)" />
3638
<param name="frame_id" value="$(arg frame_id)"/>
3739
<param name="publish_model" value="$(arg publish_model)"/>
3840
<param name="pcap" value="$(arg pcap)"/>

pandar_pointcloud/src/conversions/convert.cc

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh,
8686
: data_(new pandar_rawdata::RawData()),
8787
drv(node, private_nh, node_type, this) {
8888

89-
m_sRosVersion = "PandarSwiftROS_1.0.31";
89+
m_sRosVersion = "PandarSwiftROS_1.0.36";
9090
ROS_WARN("--------PandarSwift ROS version: %s--------\n\n",m_sRosVersion.c_str());
9191

9292
publishmodel = "";
@@ -1307,7 +1307,8 @@ void Convert::calcPointXYZIT(pandar_msgs::PandarPacket &packet, int cursor) {
13071307
}
13081308
else{
13091309
pthread_mutex_lock(&m_RedundantPointLock);
1310-
m_RedundantPointBuffer.push_back(RedundantPoint{point_index, point});
1310+
if (fabs(point.timestamp - m_OutMsgArray[cursor]->points[point_index].timestamp) > 0.01)
1311+
m_RedundantPointBuffer.push_back(RedundantPoint{point_index, point});
13111312
pthread_mutex_unlock(&m_RedundantPointLock);
13121313
}
13131314
}
@@ -1483,7 +1484,8 @@ void Convert::calcQT128PointXYZIT(pandar_msgs::PandarPacket &packet, int cursor)
14831484
}
14841485
else{
14851486
pthread_mutex_lock(&m_RedundantPointLock);
1486-
m_RedundantPointBuffer.push_back(RedundantPoint{point_index, point});
1487+
if (fabs(point.timestamp - m_OutMsgArray[cursor]->points[point_index].timestamp) > 0.01)
1488+
m_RedundantPointBuffer.push_back(RedundantPoint{point_index, point});
14871489
pthread_mutex_unlock(&m_RedundantPointLock);
14881490
}
14891491
}

pandar_pointcloud/src/conversions/driver.cc

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,12 @@ PandarDriver::PandarDriver(ros::NodeHandle node, ros::NodeHandle private_nh,
6262
int udp_port;
6363
private_nh.param("port", udp_port, (int)DATA_PORT_NUMBER);
6464

65+
std::string multicast_ip;
66+
private_nh.param("multicast_ip", multicast_ip, std::string(""));
67+
68+
std::string host_ip;
69+
private_nh.param("host_ip", host_ip, std::string(""));
70+
6571
pthread_mutex_init(&piclock, NULL);
6672

6773
m_bNeedPublish = false;
@@ -107,7 +113,7 @@ PandarDriver::PandarDriver(ros::NodeHandle node, ros::NodeHandle private_nh,
107113
packet_rate, dump_file));
108114
} else {
109115
// read data from live socket
110-
m_spInput.reset(new pandar_pointcloud::InputSocket(private_nh, udp_port));
116+
m_spInput.reset(new pandar_pointcloud::InputSocket(private_nh, host_ip, udp_port, 10010, multicast_ip));
111117
}
112118
// ROS_WARN("drive nodeType[%s]", nodeType.c_str());
113119
// ROS_WARN("drive publishmodel[%s]", publishmodel.c_str());

pandar_pointcloud/src/lib/input.cc

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@ std::string Input::getUdpVersion() {
187187
* @param private_nh ROS private handle for calling node.
188188
* @param port UDP port number
189189
*/
190-
InputSocket::InputSocket(ros::NodeHandle private_nh, uint16_t port)
190+
InputSocket::InputSocket(ros::NodeHandle private_nh, std::string host_ip, uint16_t port, uint16_t gpsport, std::string multicast_ip)
191191
: Input(private_nh, port) {
192192
sockfd_ = -1;
193193
m_u32Sequencenum = 0;
@@ -234,6 +234,18 @@ InputSocket::InputSocket(ros::NodeHandle private_nh, uint16_t port)
234234
ROS_DEBUG("Pandar socket fd is %d\n", sockfd_);
235235
int nRecvBuf = 26214400;
236236
setsockopt(sockfd_, SOL_SOCKET, SO_RCVBUF, (const char*)&nRecvBuf, sizeof(int));
237+
if(multicast_ip != ""){
238+
struct ip_mreq mreq;
239+
mreq.imr_multiaddr.s_addr=inet_addr(multicast_ip.c_str());
240+
mreq.imr_interface.s_addr = host_ip == "" ? htons(INADDR_ANY) : inet_addr(host_ip.c_str());
241+
int ret = setsockopt(sockfd_, IPPROTO_IP, IP_ADD_MEMBERSHIP, (const char *)&mreq, sizeof(mreq));
242+
if (ret < 0) {
243+
printf("Multicast IP error,set correct multicast ip address or keep it empty %s %s\n", multicast_ip.c_str(), host_ip.c_str());
244+
}
245+
else {
246+
printf("Recive data from multicast ip address %s %s\n", multicast_ip.c_str(), host_ip.c_str());
247+
}
248+
}
237249
}
238250

239251
/** @brief destructor */

0 commit comments

Comments
 (0)