Skip to content

Commit

Permalink
feat: change the default scan split way to angle
Browse files Browse the repository at this point in the history
Also change the packet rate to 750 for RS16 and 1500 for RS32

What happened.

Close #10, #11, #12
(BREAKING CHANGE: isolate scope bindings definition has changed.)

Signed-off-by: Tony Zhang <hitxfd.tony@gmail.com>
  • Loading branch information
Tony-HIT committed Aug 13, 2019
1 parent 87e1a4e commit e427de3
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 7 deletions.
10 changes: 8 additions & 2 deletions rslidar_driver/src/rsdriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,18 @@ rslidarDriver::rslidarDriver(ros::NodeHandle node, ros::NodeHandle private_nh)
// product model
if (config_.model == "RS16")
{
packet_rate = 840;
//for 0.18 degree horizontal angle resolution
//packet_rate = 840;
//for 0.2 degree horizontal angle resolution
packet_rate = 750;
model_full_name = "RS-LiDAR-16";
}
else if (config_.model == "RS32")
{
packet_rate = 1690;
//for 0.18 degree horizontal angle resolution
//packet_rate = 1690;
//for 0.2 degree horizontal angle resolution
packet_rate = 1500;
model_full_name = "RS-LiDAR-32";
}
else
Expand Down
4 changes: 3 additions & 1 deletion rslidar_pointcloud/launch/rs_lidar_16.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,15 @@
<arg name="device_ip" default="192.168.1.200" />
<arg name="msop_port" default="6699" />
<arg name="difop_port" default="7788" />
<arg name="cut_angle" default="0" doc="If set at [0, 360), cut at specific angle feature activated, otherwise use the fixed packets number mode."/>
<arg name="lidar_param_path" default="$(find rslidar_pointcloud)/data/rs_lidar_16/"/>

<node name="rslidar_node" pkg="rslidar_driver" type="rslidar_node" output="screen" >
<param name="model" value="$(arg model)"/>
<param name="device_ip" value="$(arg device_ip)" />
<param name="msop_port" value="$(arg msop_port)" />
<param name="difop_port" value="$(arg difop_port)"/>
<param name="cut_angle" value="$(arg cut_angle)"/>
<!--param name="pcap" value="path_to_pcap"/-->
</node>

Expand All @@ -19,7 +21,7 @@
<param name="angle_path" value="$(arg lidar_param_path)/angle.csv" />
<param name="channel_path" value="$(arg lidar_param_path)/ChannelNum.csv" />
<param name="max_distance" value="200"/>
<param name="min_distance" value="0.2"/>
<param name="min_distance" value="0.4"/>
<param name="resolution_type" value="0.5cm"/>
<param name="intensity_mode" value="1"/>
</node>
Expand Down
5 changes: 3 additions & 2 deletions rslidar_pointcloud/launch/rs_lidar_32.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,15 @@
<arg name="device_ip" default="192.168.1.200" />
<arg name="msop_port" default="6699" />
<arg name="difop_port" default="7788" />
<arg name="cut_angle" default="0" doc="If set at [0, 360), cut at specific angle feature activated, otherwise use the fixed packets number mode."/>
<arg name="lidar_param_path" default="$(find rslidar_pointcloud)/data/rs_lidar_32/"/>

<node name="rslidar_node" pkg="rslidar_driver" type="rslidar_node" output="screen" >
<param name="model" value="$(arg model)"/>
<param name="device_ip" value="$(arg device_ip)" />
<param name="msop_port" value="$(arg msop_port)" />
<param name="difop_port" value="$(arg difop_port)"/>
<param name="cut_angle" value="0.0" />
<param name="cut_angle" value="$(arg cut_angle)"/>
<!--param name="pcap" value="path_to_pcap"/-->
</node>

Expand All @@ -21,7 +22,7 @@
<param name="channel_path" value="$(arg lidar_param_path)/ChannelNum.csv" />
<param name="curves_rate_path" value="$(arg lidar_param_path)/CurveRate.csv" />
<param name="max_distance" value="200"/>
<param name="min_distance" value="0.2"/>
<param name="min_distance" value="0.4"/>
<param name="resolution_type" value="0.5cm"/>
<param name="intensity_mode" value="1"/>
</node>
Expand Down
2 changes: 1 addition & 1 deletion rslidar_pointcloud/src/rawdata.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ void RawData::loadConfigFile(ros::NodeHandle node, ros::NodeHandle private_nh)
end_angle_ = end_angle_ * 100;

private_nh.param("max_distance", max_distance_, 200.0f);
private_nh.param("min_distance", min_distance_, 0.2f);
private_nh.param("min_distance", min_distance_, 0.4f);

ROS_INFO_STREAM("[cloud][rawdata] distance threshlod, max: " << max_distance_ << " m, min: " << min_distance_
<< " m");
Expand Down
2 changes: 1 addition & 1 deletion rslidar_pointcloud/src/rawdata.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ static const float ROTATION_RESOLUTION = 0.01f; /**< degrees 旋转角分辨
static const uint16_t ROTATION_MAX_UNITS = 36000; /**< hundredths of degrees */

static const float DISTANCE_MAX = 200.0f; /**< meters */
static const float DISTANCE_MIN = 0.2f; /**< meters */
static const float DISTANCE_MIN = 0.4f; /**< meters */
static const float DISTANCE_RESOLUTION = 0.01f; /**< meters */
static const float DISTANCE_RESOLUTION_NEW = 0.005f; /**< meters */
static const float DISTANCE_MAX_UNITS = (DISTANCE_MAX / DISTANCE_RESOLUTION + 1.0f);
Expand Down

0 comments on commit e427de3

Please sign in to comment.