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

Add parameter to os_cloud_node to control the sensor frames publishing #153

Closed
wants to merge 2 commits into from
Closed
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
23 changes: 12 additions & 11 deletions ouster-ros/config/parameters.yaml
Original file line number Diff line number Diff line change
@@ -1,18 +1,19 @@
ouster/os_sensor:
ros__parameters:
sensor_hostname: ''
udp_dest: ''
mtp_dest: ''
sensor_hostname: ""
udp_dest: ""
mtp_dest: ""
mtp_main: false
lidar_mode: ''
timestamp_mode: ''
udp_profile_lidar: ''
metadata: ''
lidar_mode: ""
timestamp_mode: ""
udp_profile_lidar: ""
metadata: ""
lidar_port: 0
imu_port: 0
ouster/os_cloud:
ros__parameters:
sensor_frame: 'os_sensor'
lidar_frame: 'os_lidar'
imu_frame: 'os_imu'
timestamp_mode: '' # this value needs to match os_sensor/timestamp_mode
sensor_frame: "os_sensor"
lidar_frame: "os_lidar"
imu_frame: "os_imu"
timestamp_mode: "" # this value needs to match os_sensor/timestamp_mode
publish_sensor_frames: true
103 changes: 103 additions & 0 deletions ouster-ros/launch/ouster.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
#!/usr/bin/python3
# Copyright 2023 Ouster, Inc.

import lifecycle_msgs.msg
from launch import LaunchDescription
from launch.actions import EmitEvent, LogInfo, RegisterEventHandler
from launch.events import matches_action
from launch_ros.actions import LifecycleNode, Node
from launch_ros.event_handlers import OnStateTransition
from launch_ros.events.lifecycle import ChangeState
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument

def generate_launch_description():

NAMESPACE_ARG = DeclareLaunchArgument(
"namespace",
description="(str) namespace that will contain the pipeline nodes and topics",
default_value="none",
)

NAMESPACE = LaunchConfiguration("namespace", default="none")

PARAMS_ARG = DeclareLaunchArgument(
"params",
description="(str) Path to the yaml file containing the parameters for the nodes in "
"the launch file.",
default_value="",
)

PARAMS = LaunchConfiguration("params", default="")

os_sensor = LifecycleNode(
package="ouster_ros",
executable="os_sensor",
name="os_sensor",
namespace=NAMESPACE,
parameters=[PARAMS],
respawn=True,
respawn_delay=4,
)

sensor_configure_event = EmitEvent(
event=ChangeState(
lifecycle_node_matcher=matches_action(os_sensor),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,
)
)

sensor_activate_event = RegisterEventHandler(
OnStateTransition(
target_lifecycle_node=os_sensor,
goal_state="inactive",
entities=[
LogInfo(msg="os_sensor activating..."),
EmitEvent(
event=ChangeState(
lifecycle_node_matcher=matches_action(os_sensor),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE,
)
),
],
handle_once=True,
)
)

os_cloud = Node(
package="ouster_ros",
executable="os_cloud",
name="os_cloud",
namespace=NAMESPACE,
parameters=[PARAMS],
respawn=True,
respawn_delay=4,
)

os_image = Node(
package="ouster_ros",
executable="os_image",
name="os_image",
namespace=NAMESPACE,
parameters=[PARAMS],
remappings=[
([NAMESPACE, "/signal_image"], [NAMESPACE, "/intensity_image"]),
([NAMESPACE, "/signal_image2"], [NAMESPACE, "/intensity_image2"]),
([NAMESPACE, "/nearir_image"], [NAMESPACE, "/ambient_image"]),
([NAMESPACE, "/nearir_image2"], [NAMESPACE, "/ambient_image2"]),
],
respawn=True,
respawn_delay=4,
)

return LaunchDescription(
[
NAMESPACE_ARG,
PARAMS_ARG,
os_sensor,
os_cloud,
os_image,
sensor_configure_event,
sensor_activate_event,
]
)
10 changes: 9 additions & 1 deletion ouster-ros/src/os_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ class OusterCloud : public OusterProcessingNodeBase {
declare_parameter<std::string>("lidar_frame", "os_lidar");
declare_parameter<std::string>("imu_frame", "os_imu");
declare_parameter<std::string>("timestamp_mode", "");
declare_parameter<bool>("publish_sensor_frames", true);
}

void parse_parameters() {
Expand All @@ -104,6 +105,8 @@ class OusterCloud : public OusterProcessingNodeBase {

auto timestamp_mode_arg = get_parameter("timestamp_mode").as_string();
use_ros_time = timestamp_mode_arg == "TIME_FROM_ROS_TIME";

publish_sensor_frames = get_parameter("publish_sensor_frames").as_bool();
}

static double compute_scan_col_ts_spacing_ns(sensor::lidar_mode ld_mode) {
Expand All @@ -118,7 +121,10 @@ class OusterCloud : public OusterProcessingNodeBase {
RCLCPP_INFO(get_logger(),
"OusterCloud: retrieved new sensor metadata!");
info = sensor::parse_metadata(metadata_msg->data);
send_static_transforms();
if (publish_sensor_frames)
{
send_static_transforms();
}
n_returns = get_n_returns();
create_lidarscan_objects();
compute_scan_ts = [this](const auto& ts_v) {
Expand Down Expand Up @@ -349,6 +355,8 @@ class OusterCloud : public OusterProcessingNodeBase {
std::string imu_frame;
std::string lidar_frame;

bool publish_sensor_frames;

tf2_ros::StaticTransformBroadcaster tf_bcast;

bool use_ros_time;
Expand Down