Skip to content

Commit

Permalink
Rename nodelets_os namesapce to ouster_ros +
Browse files Browse the repository at this point in the history
Rename nodelets_os.xml to ouster_ros_nodelet.xml +
Wrap all classes with ouster_ros +
always default no_bond +
Fix Dockerfile build
formatting
  • Loading branch information
Samahu committed Jul 20, 2023
1 parent 62a24f8 commit c3be165
Show file tree
Hide file tree
Showing 28 changed files with 201 additions and 198 deletions.
12 changes: 6 additions & 6 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,15 +77,15 @@ target_link_libraries(ouster_ros PUBLIC ${catkin_LIBRARIES} ouster_build pcl_com
add_dependencies(ouster_ros ${PROJECT_NAME}_gencpp)

# ==== Executables ====
add_library(nodelets_os
add_library(${PROJECT_NAME}_nodelets
src/os_sensor_nodelet_base.cpp
src/os_sensor_nodelet.cpp
src/os_replay_nodelet.cpp
src/os_cloud_nodelet.cpp
src/os_image_nodelet.cpp
src/os_driver_nodelet.cpp)
target_link_libraries(nodelets_os ouster_ros ${catkin_LIBRARIES})
add_dependencies(nodelets_os ${PROJECT_NAME}_gencpp)
target_link_libraries(${PROJECT_NAME}_nodelets ouster_ros ${catkin_LIBRARIES})
add_dependencies(${PROJECT_NAME}_nodelets ${PROJECT_NAME}_gencpp)

# ==== Test ====
if(CATKIN_ENABLE_TESTING)
Expand All @@ -96,8 +96,8 @@ endif()
# ==== Install ====
install(
TARGETS
ouster_ros
nodelets_os
${PROJECT_NAME}
${PROJECT_NAME}_nodelets
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
Expand All @@ -111,7 +111,7 @@ install(
install(
FILES
LICENSE
nodelets_os.xml
${PROJECT_NAME}_nodelets.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

Expand Down
9 changes: 5 additions & 4 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -54,11 +54,12 @@ FROM build-env
SHELL ["/bin/bash", "-c"]

ENV CXXFLAGS="-Werror -Wno-deprecated-declarations"
RUN /opt/ros/$ROS_DISTRO/env.sh catkin_make \
-DCMAKE_BUILD_TYPE=Release --make-args tests \
&& /opt/ros/$ROS_DISTRO/env.sh catkin_make install
RUN /opt/ros/$ROS_DISTRO/env.sh catkin_make \
-DCMAKE_BUILD_TYPE=Release \
&& /opt/ros/$ROS_DISTRO/env.sh catkin_make install

RUN source ./devel/setup.bash && rosrun ouster_ros ouster_ros_test
RUN /opt/ros/$ROS_DISTRO/env.sh catkin_make --make-args tests \
&& source ./devel/setup.bash && rosrun ouster_ros ouster_ros_test

# Entrypoint for running Ouster ros:
#
Expand Down
34 changes: 15 additions & 19 deletions include/ouster_ros/os_ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud2.h>

#include <chrono>
#include <string>
Expand All @@ -40,13 +40,13 @@ using ns = std::chrono::nanoseconds;
bool is_legacy_lidar_profile(const sensor::sensor_info& info);

/**
* Gets the number of point cloud returns that this sensor_info object represents
* Gets the number of point cloud returns that this sensor_info object
* represents
* @param[in] info sensor_info
* @return number of returns
*/
int get_n_returns(const sensor::sensor_info& info);


/**
* Gets the number beams based on supplied sensor_info
* @param[in] info sensor_info
Expand All @@ -71,9 +71,9 @@ std::string topic_for_return(const std::string& topic_base, int return_idx);
* @return ROS sensor message with fields populated from the packet
*/
sensor_msgs::Imu packet_to_imu_msg(const ouster::sensor::packet_format& pf,
const ros::Time& timestamp,
const std::string& frame,
const uint8_t* buf);
const ros::Time& timestamp,
const std::string& frame,
const uint8_t* buf);

/**
* Parse an imu packet message into a ROS imu message
Expand All @@ -84,9 +84,9 @@ sensor_msgs::Imu packet_to_imu_msg(const ouster::sensor::packet_format& pf,
* @return ROS sensor message with fields populated from the packet
*/
sensor_msgs::Imu packet_to_imu_msg(const PacketMsg& pm,
const ros::Time& timestamp,
const std::string& frame,
const sensor::packet_format& pf);
const ros::Time& timestamp,
const std::string& frame,
const sensor::packet_format& pf);

/**
* Populate a PCL point cloud from a LidarScan.
Expand Down Expand Up @@ -132,8 +132,8 @@ void scan_to_cloud_f(ouster::PointsF& points,
* @return a ROS message containing the point cloud
*/
sensor_msgs::PointCloud2 cloud_to_cloud_msg(const Cloud& cloud,
const ros::Time& timestamp,
const std::string& frame);
const ros::Time& timestamp,
const std::string& frame);

/**
* Convert transformation matrix return by sensor to ROS transform
Expand All @@ -148,7 +148,6 @@ geometry_msgs::TransformStamped transform_to_tf_msg(
const ouster::mat4d& mat, const std::string& frame,
const std::string& child_frame, ros::Time timestamp);


/**
* Convert transformation matrix return by sensor to ROS transform
* @param[in] ls lidar scan object
Expand All @@ -159,12 +158,9 @@ geometry_msgs::TransformStamped transform_to_tf_msg(
* @return ROS message suitable for publishing as a LaserScan
*/
sensor_msgs::LaserScan lidar_scan_to_laser_scan_msg(
const ouster::LidarScan& ls,
const ros::Time& timestamp,
const std::string &frame,
const ouster::sensor::lidar_mode lidar_mode,
const uint16_t ring,
const int return_index);
const ouster::LidarScan& ls, const ros::Time& timestamp,
const std::string& frame, const ouster::sensor::lidar_mode lidar_mode,
const uint16_t ring, const int return_index);

namespace impl {
sensor::ChanField suitable_return(sensor::ChanField input_field, bool second);
Expand All @@ -191,6 +187,6 @@ inline ouster::img_t<T> get_or_fill_zero(sensor::ChanField field,

ros::Time ts_to_ros_time(uint64_t ts);

} // namespace impl
} // namespace impl

} // namespace ouster_ros
4 changes: 2 additions & 2 deletions include/ouster_ros/os_sensor_nodelet_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

#include <ouster/types.h>

namespace nodelets_os {
namespace ouster_ros {

class OusterSensorNodeletBase : public nodelet::Nodelet {
protected:
Expand Down Expand Up @@ -40,4 +40,4 @@ class OusterSensorNodeletBase : public nodelet::Nodelet {
ros::Publisher metadata_pub;
};

} // namespace nodelets_os
} // namespace ouster_ros
4 changes: 2 additions & 2 deletions launch/common.launch
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_cloud_node"
output="screen" required="true"
args="load nodelets_os/OusterCloud os_nodelet_mgr $(arg _no_bond)">
args="load ouster_ros/OusterCloud os_nodelet_mgr $(arg _no_bond)">
<param name="~/tf_prefix" type="str" value="$(arg tf_prefix)"/>
<param name="~/sensor_frame" value="$(arg sensor_frame)"/>
<param name="~/lidar_frame" value="$(arg lidar_frame)"/>
Expand All @@ -53,7 +53,7 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="img_node"
output="screen" required="true"
args="load nodelets_os/OusterImage os_nodelet_mgr $(arg _no_bond)">
args="load ouster_ros/OusterImage os_nodelet_mgr $(arg _no_bond)">
</node>
</group>

Expand Down
6 changes: 3 additions & 3 deletions launch/driver.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,15 +36,15 @@
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
<arg name="point_cloud_frame" default=" "
doc="which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
<arg if="$(arg no_bond)" name="_no_bond" value="--no-bond"/>
<arg unless="$(arg no_bond)" name="_no_bond" value="" />
<arg unless="$(arg no_bond)" name="_no_bond" value=" "/>

<arg name="proc_mask" default="IMG|PCL|IMU|SCAN" doc="
use any combination of the 4 flags to enable or disable specific processors"/>
Expand All @@ -63,7 +63,7 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_driver"
output="screen" required="true"
args="load nodelets_os/OusterDriver os_nodelet_mgr $(arg _no_bond)">
args="load ouster_ros/OusterDriver os_nodelet_mgr $(arg _no_bond)">
<param name="~/sensor_hostname" type="str" value="$(arg sensor_hostname)"/>
<param name="~/udp_dest" type="str" value="$(arg udp_dest)"/>
<param name="~/lidar_port" type="int" value="$(arg lidar_port)"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/record.launch
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
<arg name="point_cloud_frame" default=" "
doc="which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>
Expand Down Expand Up @@ -67,7 +67,7 @@
<node pkg="nodelet" type="nodelet" name="os_node"
output="screen" required="true"
launch-prefix="bash -c 'sleep 1; $0 $@' "
args="load nodelets_os/OusterSensor os_nodelet_mgr">
args="load ouster_ros/OusterSensor os_nodelet_mgr">
<param name="~/sensor_hostname" type="str" value="$(arg sensor_hostname)"/>
<param name="~/udp_dest" type="str" value="$(arg udp_dest)"/>
<param name="~/lidar_port" type="int" value="$(arg lidar_port)"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/replay.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
<arg name="point_cloud_frame" default=" "
doc="which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>
Expand Down Expand Up @@ -49,7 +49,7 @@
<node if="$(arg _use_metadata_file)" pkg="nodelet" type="nodelet"
name="os_node" output="screen" required="true"
launch-prefix="bash -c 'sleep 3; $0 $@' "
args="load nodelets_os/OusterReplay os_nodelet_mgr">
args="load ouster_ros/OusterReplay os_nodelet_mgr">
<param name="~/metadata" value="$(arg metadata)"/>
</node>
</group>
Expand Down
6 changes: 3 additions & 3 deletions launch/sensor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,15 +36,15 @@
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
<arg name="point_cloud_frame" default=" "
doc="which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
<arg if="$(arg no_bond)" name="_no_bond" value="--no-bond"/>
<arg unless="$(arg no_bond)" name="_no_bond" value="" />
<arg unless="$(arg no_bond)" name="_no_bond" value=" "/>

<arg name="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
Expand All @@ -70,7 +70,7 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_node"
output="screen" required="true"
args="load nodelets_os/OusterSensor os_nodelet_mgr $(arg _no_bond)">
args="load ouster_ros/OusterSensor os_nodelet_mgr $(arg _no_bond)">
<param name="~/sensor_hostname" type="str" value="$(arg sensor_hostname)"/>
<param name="~/udp_dest" type="str" value="$(arg udp_dest)"/>
<param name="~/lidar_port" type="int" value="$(arg lidar_port)"/>
Expand Down
6 changes: 3 additions & 3 deletions launch/sensor_mtp.launch
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,15 @@
doc="sets name of choice for the os_lidar tf frame, value can not be empty"/>
<arg name="imu_frame" default="os_imu"
doc="sets name of choice for the os_imu tf frame, value can not be empty"/>
<arg name="point_cloud_frame" default=""
<arg name="point_cloud_frame" default=" "
doc="which frame to be used when publishing PointCloud2 or LaserScan messages.
Choose between the value of sensor_frame or lidar_frame, leaving this value empty
would set lidar_frame to be the frame used when publishing these messages."/>

<arg name="no_bond" default="false"
doc="request no bond setup when nodelets are created"/>
<arg if="$(arg no_bond)" name="_no_bond" value="--no-bond"/>
<arg unless="$(arg no_bond)" name="_no_bond" value="" />
<arg unless="$(arg no_bond)" name="_no_bond" value=" "/>

<arg name="dynamic_transforms_broadcast" default="false"
doc="static or dynamic transforms broadcast"/>
Expand All @@ -74,7 +74,7 @@
<group ns="$(arg ouster_ns)">
<node pkg="nodelet" type="nodelet" name="os_node"
output="screen" required="true"
args="load nodelets_os/OusterSensor os_nodelet_mgr $(arg _no_bond)">
args="load ouster_ros/OusterSensor os_nodelet_mgr $(arg _no_bond)">
<param name="~/sensor_hostname" type="str" value="$(arg sensor_hostname)"/>
<param name="~/udp_dest" type="str" value="$(arg udp_dest)"/>
<param name="~/mtp_dest" type="str" value="$(arg mtp_dest)"/>
Expand Down
27 changes: 0 additions & 27 deletions nodelets_os.xml

This file was deleted.

27 changes: 27 additions & 0 deletions ouster_ros_nodelets.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<library path="lib/libouster_ros_nodelets">
<class name="ouster_ros/OusterSensor" type="ouster_ros::OusterSensor" base_class_type="nodelet::Nodelet">
<description>
A nodelet that connects to an Ouster sensor and publish incoming imu and lidar packets to other ros nodes.
</description>
</class>
<class name="ouster_ros/OusterReplay" type="ouster_ros::OusterReplay" base_class_type="nodelet::Nodelet">
<description>
A nodelet that can load up existing Ouster recordings and replay them.
</description>
</class>
<class name="ouster_ros/OusterCloud" type="ouster_ros::OusterCloud" base_class_type="nodelet::Nodelet">
<description>
A nodelet that process incoming Ouster lidar packets and publishes a corresponding point cloud.
</description>
</class>
<class name="ouster_ros/OusterImage" type="ouster_ros::OusterImage" base_class_type="nodelet::Nodelet">
<description>
A nodelet that processes Ouster point clouds and publish them as depth images.
</description>
</class>
<class name="ouster_ros/OusterDriver" type="ouster_ros::OusterDriver" base_class_type="nodelet::Nodelet">
<description>
A nodelet that combines the capabilities of OusterSensor, OusterCloud and OusterImage into a single nodelet.
</description>
</class>
</library>
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,6 @@
<test_depend>gtest</test_depend>

<export>
<nodelet plugin="${prefix}/nodelets_os.xml"/>
<nodelet plugin="${prefix}/ouster_ros_nodelets.xml"/>
</export>
</package>
Loading

0 comments on commit c3be165

Please sign in to comment.