Skip to content

Commit

Permalink
formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
lenpuc committed Jun 19, 2024
1 parent 8e5acfc commit 2db7ecb
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions src/SickSafetyscannersRos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -429,8 +429,9 @@ SickSafetyscannersRos::createLaserScanMessage(const sick::datastructure::Data& d

scan.angle_min = sick::degToRad(data.getDerivedValuesPtr()->getStartAngle() + m_angle_offset);
// if the scan points vector is empty, the angle max is set to the angle min
scan.angle_max = scan_points.empty() ? scan.angle_min
: sick::degToRad(scan_points.back().getAngle() + m_angle_offset);
scan.angle_max = scan_points.empty()
? scan.angle_min
: sick::degToRad(scan_points.back().getAngle() + m_angle_offset);
scan.angle_increment = sick::degToRad(data.getDerivedValuesPtr()->getAngularBeamResolution());
boost::posix_time::microseconds time_increment =
boost::posix_time::microseconds(data.getDerivedValuesPtr()->getInterbeamPeriod());
Expand Down

0 comments on commit 2db7ecb

Please sign in to comment.