Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Param for lowering used channel count #338

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -241,6 +241,7 @@ You can also optionally specify:
* ``lidar_mode:=<mode>`` where mode is one of ``512x10``, ``512x20``, ``1024x10``, ``1024x20``, or
``2048x10``, and
* ``viz:=true`` to visualize the sensor output, if you have the rviz ROS package installed
* ``channel_reduction_ratio:=<int>`` to reduce the amount of channels used for the output cloud. So a 128 beam lidar with a channel_reduction_ratio of 4 would result in a simulated 32 beam lidar. (Value has to be 2^n)


Recording Data
Expand Down
3 changes: 2 additions & 1 deletion ouster_ros/include/ouster_ros/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,10 +63,11 @@ sensor_msgs::Imu packet_to_imu_msg(const PacketMsg& pm,
* @param ls input lidar data
* @param return_index index of return desired starting at 0
* @param cloud output pcl pointcloud to populate
* @param channel_reduction_ratio ratio at which to reduce channel count
*/
void scan_to_cloud(const ouster::XYZLut& xyz_lut,
ouster::LidarScan::ts_t scan_ts, const ouster::LidarScan& ls,
ouster_ros::Cloud& cloud, int return_index = 0);
ouster_ros::Cloud& cloud, uint32_t channel_reduction_ratio, int return_index = 0);

/**
* Serialize a PCL point cloud to a ROS message
Expand Down
8 changes: 8 additions & 0 deletions ouster_ros/ouster.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<arg name="rviz_config" default="-d $(find ouster_ros)/viz.rviz" doc="optional rviz config file"/>
<arg name="tf_prefix" default="" doc="namespace for tf transforms"/>
<arg name="udp_profile_lidar" default="" doc="lidar packet profile: LEGACY, RNG19_RFL8_SIG16_NIR16_DUAL"/>
<arg name="channel_reduction_ratio" default="1" doc="the ratio at wich to reduce channel count, can be used to simulate a lower beam count lidar (VALUE MUST BE 2^n)"/>

<node pkg="ouster_ros" name="os_node" type="os_node" output="screen" required="true">
<param name="~/lidar_mode" type="string" value="$(arg lidar_mode)"/>
Expand All @@ -30,6 +31,13 @@
<remap from="~/lidar_packets" to="/os_node/lidar_packets"/>
<remap from="~/imu_packets" to="/os_node/imu_packets"/>
<param name="~/tf_prefix" value="$(arg tf_prefix)"/>
<param name="~/channel_reduction_ratio" value="$(arg channel_reduction_ratio)"/>
</node>

<node pkg="ouster_ros" type="img_node" name="img_node" output="screen" required="false">
<remap from="~/os_config" to="/os_node/os_config"/>
<remap from="~/points" to="/os_cloud_node/points"/>
<param name="~/channel_reduction_ratio" value="$(arg channel_reduction_ratio)"/>
</node>

<node if="$(arg viz)" pkg="rviz" name="rviz" type="rviz" args="$(arg rviz_config)" output="screen" required="true" />
Expand Down
4 changes: 3 additions & 1 deletion ouster_ros/src/img_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ int main(int argc, char** argv) {
ros::init(argc, argv, "img_node");
ros::NodeHandle nh("~");

uint32_t channel_reduction_ratio = nh.param("channel_reduction_ratio", 1);

ouster_ros::OSConfigSrv cfg{};
auto client = nh.serviceClient<ouster_ros::OSConfigSrv>("os_config");
client.waitForExistence();
Expand All @@ -61,7 +63,7 @@ int main(int argc, char** argv) {
}

auto info = sensor::parse_metadata(cfg.response.metadata);
size_t H = info.format.pixels_per_column;
size_t H = info.format.pixels_per_column / channel_reduction_ratio;
size_t W = info.format.columns_per_frame;

auto udp_profile_lidar = info.format.udp_profile_lidar;
Expand Down
15 changes: 13 additions & 2 deletions ouster_ros/src/os_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ int main(int argc, char** argv) {
ros::init(argc, argv, "os_cloud_node");
ros::NodeHandle nh("~");

uint32_t channel_reduction_ratio = nh.param("channel_reduction_ratio", 1);

auto tf_prefix = nh.param("tf_prefix", std::string{});
if (!tf_prefix.empty() && tf_prefix.back() != '/') tf_prefix.append("/");
auto sensor_frame = tf_prefix + "os_sensor";
Expand All @@ -48,6 +50,15 @@ int main(int argc, char** argv) {
uint32_t W = info.format.columns_per_frame;
auto udp_profile_lidar = info.format.udp_profile_lidar;

if(channel_reduction_ratio != 1){
if(channel_reduction_ratio <= 0)
throw std::invalid_argument("channel_reduction_ratio must be greater than zero");
if(H <= channel_reduction_ratio)
throw std::invalid_argument("channel_reduction_ratio must be less than or equal to the lidar channel count");
if(ceil(log2(channel_reduction_ratio)) != floor(log2(channel_reduction_ratio)))
throw std::invalid_argument("channel_reduction_ratio must be 2^n");
}

const int n_returns =
(udp_profile_lidar == sensor::UDPProfileLidar::PROFILE_LIDAR_LEGACY)
? 1
Expand All @@ -71,7 +82,7 @@ int main(int argc, char** argv) {
auto xyz_lut = ouster::make_xyz_lut(info);

ouster::LidarScan ls{W, H, udp_profile_lidar};
Cloud cloud{W, H};
Cloud cloud{W, H / channel_reduction_ratio};

ouster::ScanBatcher batch(W, pf);

Expand All @@ -83,7 +94,7 @@ int main(int argc, char** argv) {
});
if (h != ls.headers.end()) {
for (int i = 0; i < n_returns; i++) {
scan_to_cloud(xyz_lut, h->timestamp, ls, cloud, i);
scan_to_cloud(xyz_lut, h->timestamp, ls, cloud, channel_reduction_ratio, i);
lidar_pubs[i].publish(ouster_ros::cloud_to_cloud_msg(
cloud, h->timestamp, sensor_frame));
}
Expand Down
16 changes: 12 additions & 4 deletions ouster_ros/src/ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,17 @@ sensor::ChanField suitable_return(sensor::ChanField input_field, bool second) {

void scan_to_cloud(const ouster::XYZLut& xyz_lut,
ouster::LidarScan::ts_t scan_ts, const ouster::LidarScan& ls,
ouster_ros::Cloud& cloud, int return_index) {
ouster_ros::Cloud& cloud, uint32_t channel_reduction_ratio, int return_index) {
if(channel_reduction_ratio != 1){
if(channel_reduction_ratio <= 0)
throw std::invalid_argument("channel_reduction_ratio must be greater than zero");
if(ls.h <= channel_reduction_ratio)
throw std::invalid_argument("channel_reduction_ratio must be less than or equal to the lidar channel count");
if(ceil(log2(channel_reduction_ratio)) != floor(log2(channel_reduction_ratio)))
throw std::invalid_argument("channel_reduction_ratio must be 2^n");
}
bool second = (return_index == 1);
cloud.resize(ls.w * ls.h);
cloud.resize(ls.w * ls.h / channel_reduction_ratio);

ouster::img_t<uint16_t> near_ir;
ouster::impl::visit_field(
Expand All @@ -120,11 +128,11 @@ void scan_to_cloud(const ouster::XYZLut& xyz_lut,

auto points = ouster::cartesian(range, xyz_lut);

for (auto u = 0; u < ls.h; u++) {
for (auto u = 0, w = 0; u < ls.h; u += channel_reduction_ratio, w++) {
for (auto v = 0; v < ls.w; v++) {
const auto xyz = points.row(u * ls.w + v);
const auto ts = (ls.header(v).timestamp - scan_ts).count();
cloud(v, u) = ouster_ros::Point{
cloud(v, w) = ouster_ros::Point{
{{static_cast<float>(xyz(0)), static_cast<float>(xyz(1)),
static_cast<float>(xyz(2)), 1.0f}},
static_cast<float>(signal(u, v)),
Expand Down