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

Fix Coverity issues + remove empty warning log #3053

Merged
merged 6 commits into from
Mar 21, 2024
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
20 changes: 16 additions & 4 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,11 @@ SyncedImuPublisher::SyncedImuPublisher(rclcpp::Publisher<sensor_msgs::msg::Imu>:

SyncedImuPublisher::~SyncedImuPublisher()
{
PublishPendingMessages();
try
{
PublishPendingMessages();
}
catch(...){} // Not allowed to throw from Dtor
}

void SyncedImuPublisher::Publish(sensor_msgs::msg::Imu imu_msg)
Expand Down Expand Up @@ -149,10 +153,14 @@ BaseRealSenseNode::~BaseRealSenseNode()
_monitoring_pc->join();
}
clearParameters();
for(auto&& sensor : _available_ros_sensors)
try
{
sensor->stop();
for(auto&& sensor : _available_ros_sensors)
{
sensor->stop();
}
}
catch(...){} // Not allowed to throw from Dtor
}

void BaseRealSenseNode::hardwareResetRequest()
Expand Down Expand Up @@ -643,7 +651,11 @@ void BaseRealSenseNode::multiple_message_callback(rs2::frame frame, imu_sync_met

bool BaseRealSenseNode::setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
{
ROS_WARN_ONCE(time_domain == RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME ? "Frame metadata isn't available! (frame_timestamp_domain = RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)" : "");
if (time_domain == RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)
{
ROS_WARN_ONCE("Frame metadata isn't available! (frame_timestamp_domain = RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME)");
}

if (time_domain == RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK)
{
ROS_WARN("frame's time domain is HARDWARE_CLOCK. Timestamps may reset periodically.");
Expand Down
4 changes: 3 additions & 1 deletion realsense2_camera/src/profile_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ std::string applyTemplateName(std::string template_name, stream_index_pair sip)
const std::string stream_name(create_graph_resource_name(STREAM_NAME(sip)));
char* param_name = new char[template_name.size() + stream_name.size()];
sprintf(param_name, template_name.c_str(), stream_name.c_str());
return std::string(param_name);
std::string full_name(param_name);
delete [] param_name;
return full_name;
}

void ProfilesManager::registerSensorQOSParam(std::string template_name,
Expand Down
8 changes: 6 additions & 2 deletions realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,8 +78,12 @@ RosSensor::RosSensor(rs2::sensor sensor,

RosSensor::~RosSensor()
{
clearParameters();
stop();
try
{
clearParameters();
stop();
}
catch(...){} // Not allowed to throw from Dtor
}

void RosSensor::setParameters(bool is_rosbag_file)
Expand Down
Loading