Skip to content
Merged
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
6 changes: 3 additions & 3 deletions realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,7 +244,7 @@ void RosSensor::stop()
{
if (get_active_streams().size() == 0)
return;
ROS_INFO_STREAM("Stop Sensor: " << get_info(RS2_CAMERA_INFO_NAME));
ROS_INFO_STREAM("Stop Sensor: " << rs2_to_ros(get_info(RS2_CAMERA_INFO_NAME)));
_frequency_diagnostics.clear();

try
Expand Down Expand Up @@ -337,13 +337,13 @@ bool RosSensor::getUpdatedProfiles(std::vector<stream_profile>& wanted_profiles)
profile_manager->addWantedProfiles(wanted_profiles);
}

ROS_DEBUG_STREAM(get_info(RS2_CAMERA_INFO_NAME) << ":" << "active_profiles.size() = " << active_profiles.size());
ROS_DEBUG_STREAM(rs2_to_ros(get_info(RS2_CAMERA_INFO_NAME)) << ":" << "active_profiles.size() = " << active_profiles.size());
for (auto& profile : active_profiles)
{
ROS_DEBUG_STREAM("Sensor profile: " << ProfilesManager::profile_string(profile));
}

ROS_DEBUG_STREAM(get_info(RS2_CAMERA_INFO_NAME) << ":" << "wanted_profiles");
ROS_DEBUG_STREAM(rs2_to_ros(get_info(RS2_CAMERA_INFO_NAME)) << ":" << "wanted_profiles");
for (auto& profile : wanted_profiles)
{
ROS_DEBUG_STREAM("Sensor profile: " << ProfilesManager::profile_string(profile));
Expand Down
6 changes: 3 additions & 3 deletions realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ void BaseRealSenseNode::setAvailableSensors()

for(auto&& sensor : _dev_sensors)
{
const std::string module_name(sensor.get_info(RS2_CAMERA_INFO_NAME));
const std::string module_name(rs2_to_ros(sensor.get_info(RS2_CAMERA_INFO_NAME)));
std::unique_ptr<RosSensor> rosSensor;
if (sensor.is<rs2::depth_sensor>() ||
sensor.is<rs2::color_sensor>() ||
Expand Down Expand Up @@ -304,7 +304,7 @@ void BaseRealSenseNode::updateSensors()
try{
for(auto&& sensor : _available_ros_sensors)
{
std::string module_name(sensor->get_info(RS2_CAMERA_INFO_NAME));
std::string module_name(rs2_to_ros(sensor->get_info(RS2_CAMERA_INFO_NAME)));
// if active_profiles != wanted_profiles: stop sensor.
std::vector<stream_profile> wanted_profiles;

Expand Down Expand Up @@ -386,7 +386,7 @@ void BaseRealSenseNode::getDeviceInfo(const realsense2_camera_msgs::srv::DeviceI

for(auto&& sensor : _available_ros_sensors)
{
sensors_names << create_graph_resource_name(sensor->get_info(RS2_CAMERA_INFO_NAME)) << ",";
sensors_names << create_graph_resource_name(rs2_to_ros(sensor->get_info(RS2_CAMERA_INFO_NAME))) << ",";
}

res->sensors = sensors_names.str().substr(0, sensors_names.str().size()-1);
Expand Down