Skip to content

Conversation

@mattalvarado
Copy link
Collaborator

@mattalvarado mattalvarado commented May 31, 2025

Use the new LibMultiSense API as the base for the multisense_ros2 driver.

To properly use this driver you must use MultiSense firmware >= v7.22. See https://docs.carnegierobotics.com/firmware/update.html for update instructions

Notable changes include:

  • Consolidation of nodes into a single multisense.cpp node
  • Use the generate_parameter_library to eliminate substantial ROS2 parameter overhead
  • Use DDS connection callbacks to mimic ROS1 lazy publisher behavior
  • Publish all messages as unique_ptr's to support intraprocess comms
  • Use the new LibMultiSense API's utility functions to create color images, point clouds, and depth images
  • Cleanup/Improve custom message types
  • Be much more pedantic on parameter applications
  • Improve parameter naming to better match ROS2 conventions
  • Only support ROS2 Jazzy

@mattalvarado mattalvarado changed the title New libmultisense api use the new libmultisense api May 31, 2025
…robotics/multisense_ros2 into malvarado/new_libmultisense_api
const rclcpp::NodeOptions& options,
std::unique_ptr<multisense::Channel> channel,
const std::string& tf_prefix,
bool use_image_transport,
Copy link

@ziparker ziparker Aug 1, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nbd: we could maybe do something to help clarify the purpose of the bool args in calling code (eg this would look like Multisense(..., false, true))

// Device stream control

size_t num_subscribers(const rclcpp::Node::SharedPtr node, const std::string &topic);
size_t num_subscribers(const rclcpp::Node* node, const std::string &topic);
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nit: make these methods const, and maybe switch to const Node &?
they are private, so it isn't much of a practical concern

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe I started with a const ref, but I need to pass the pointer to the current node via this for things to work properly

const size_t num_fields = ros_point_cloud.fields.size();

//
// Unfortunately we need to iterate and write our points to the output buffer since we need to
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

not sure what the receiving end looks like, but just curious if it can use the field configuration to pull the color channels out of 3 separate uint8 fields instead of 1 float32?


//
// If our main image pair does not support color, make sure we explicitly disable white balance. If
// we could undeclare the parameter
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is this an unfinished comment?

looks like parameters can be undeclared by setting to rclcpp::PARAMETER_NOT_SET?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unfortunately rclcpp::PARAMETER_NOT_SET doesn't actually work

@mattalvarado mattalvarado merged commit 09e4508 into master Oct 6, 2025
1 check passed
@mattalvarado mattalvarado deleted the malvarado/new_libmultisense_api branch October 6, 2025 16:02
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants