Skip to content

Commit

Permalink
Update files to match new pre-commit updates
Browse files Browse the repository at this point in the history
  • Loading branch information
cbrxyz committed Jun 1, 2023
1 parent 078ee8a commit 3728f5c
Show file tree
Hide file tree
Showing 10 changed files with 18 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ def decode_parameters(cls, parameters):
if not isinstance(parsed, list) or len(parsed) != 3:
raise err
for i in range(3):
if not (isinstance(parsed[i], int) or isinstance(parsed[i], float)):
if not (isinstance(parsed[i], (int, float))):
raise err
return parsed

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,15 +70,15 @@ class Device
result.header.frame_id = frame_id;
result.header.stamp = ros::Time::now();

result.orientation_covariance[0] = -1; // indicate no orientation data
result.orientation_covariance[0] = -1; // indicate no orientation data

static const double GYRO_CONVERSION = 0.05 * (2 * M_PI / 360); // convert to deg/s and then to rad/s
result.angular_velocity.x = get16(data + 4 + 2 * 0) * GYRO_CONVERSION;
result.angular_velocity.y = get16(data + 4 + 2 * 1) * GYRO_CONVERSION;
result.angular_velocity.z = get16(data + 4 + 2 * 2) * GYRO_CONVERSION;
result.angular_velocity_covariance[0] = result.angular_velocity_covariance[4] =
result.angular_velocity_covariance[8] =
pow(0.9 * (2 * M_PI / 360), 2); // 0.9 deg/sec rms converted to rad/sec and then squared
pow(0.9 * (2 * M_PI / 360), 2); // 0.9 deg/sec rms converted to rad/sec and then squared

static const double ACC_CONVERSION = 3.33e-3 * 9.80665; // convert to g's and then to m/s^2
result.linear_acceleration.x = -get16(data + 10 + 2 * 0) * ACC_CONVERSION;
Expand All @@ -99,9 +99,9 @@ class Device
mag_result.magnetic_field_covariance[8] =
pow(1.25e-3 * 0.0001, 2); // 1.25 mgauss converted to tesla and then squared

getu16(data + 0); // flags unused
getu16(data + 2) * 2.418e-3; // supply voltage unused
get16(data + 22) * 0.14 + 25; // temperature unused
getu16(data + 0); // flags unused
getu16(data + 2) * 2.418e-3; // supply voltage unused
get16(data + 22) * 0.14 + 25; // temperature unused

return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ class Device

void send_heartbeat()
{
send_packet(ByteVec()); // heartbeat
send_packet(ByteVec()); // heartbeat
uint8_t msg[] = { 4, 1, 20 };
send_packet(ByteVec(msg, msg + sizeof(msg) / sizeof(msg[0]))); // StartPublishing 20hz
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1494,7 +1494,7 @@ void anisotropic_diffusion(const Mat &src, Mat &dest, int t_max)
if (i == 0 || i == x0.rows - 1 || j == 0 || j == x0.cols - 1) // conduction coefficient set to
d = 1; // 1 p633 after equation 13
else
d = 1.0 / (1 + (gx * gx + 0 * gy * gy) * K2); // expression of g(gradient(I))
d = 1.0 / (1 + (gx * gx + 0 * gy * gy) * K2); // expression of g(gradient(I))
// d =-exp(-(gx*gx+gy*gy)*K2); // expression of g(gradient(I))
D.at<float>(i, j) = d;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ struct hashtable
using std::move;
} // namespace details
} // namespace backward
#else // NOT BACKWARD_ATLEAST_CXX11
#else // NOT BACKWARD_ATLEAST_CXX11
#include <map>
namespace backward
{
Expand Down Expand Up @@ -752,7 +752,7 @@ class StackTraceImpl<system_tag::linux_tag> : public StackTraceLinuxImplHolder
};
};

#else // BACKWARD_HAS_UNWIND == 0
#else // BACKWARD_HAS_UNWIND == 0

template <>
class StackTraceImpl<system_tag::linux_tag> : public StackTraceLinuxImplHolder
Expand Down Expand Up @@ -1902,7 +1902,7 @@ class Colorize
bool _istty;
};

#else // ndef BACKWARD_SYSTEM_LINUX
#else // ndef BACKWARD_SYSTEM_LINUX

namespace Color
{
Expand Down Expand Up @@ -2152,7 +2152,7 @@ class SignalHandling

StackTrace st;
void* error_addr = 0;
#ifdef REG_RIP // x86_64
#ifdef REG_RIP // x86_64
error_addr = reinterpret_cast<void*>(uctx->uc_mcontext.gregs[REG_RIP]);
#elif defined(REG_EIP) // x86_32
error_addr = reinterpret_cast<void*>(uctx->uc_mcontext.gregs[REG_EIP]);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ void growRoute(const vector<uint8_t>& partial, const vector<uint8_t>& occupied,
auto next_partial = partial;
next_partial.push_back(new_elem);

auto next_tails = getHoodIdxs(new_elem, true); // true --> include border
auto next_tails = getHoodIdxs(new_elem, true); // true --> include border
auto find_exit_itr = find(next_tails.begin(), next_tails.end(), exit);
if (find_exit_itr != next_tails.end() && *find_exit_itr != tail) // add to cache if exit is a possible next tail
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ cv::Mat rotateKernel(const cv::Mat &kernel, float theta, bool deg, bool no_expan
theta = deg ? theta : theta * mil_tools::PI / 180.0f;
cv::Point2f c_org{ kernel.cols * 0.5f, kernel.rows * 0.5f }; // center of original

if (no_expand) // rotates without expanding the canvas
if (no_expand) // rotates without expanding the canvas
{
cv::Mat result;
cv::Mat rot_mat = cv::getRotationMatrix2D(c_org, theta, 1.0f);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ void OgridManager::update_config(Config const& config)
ogrid_.info.height = height_meters_ / resolution_meters_per_cell_;
ogrid_.info.origin.position.x = -1. * width_meters_ / 2.; //-1. * width_meters_ * resolution_meters_per_cell_ / 2.;
ogrid_.info.origin.position.y =
-1. * height_meters_ / 2.; // -1. * height_meters_ * resolution_meters_per_cell_ / 2.;
-1. * height_meters_ / 2.; // -1. * height_meters_ * resolution_meters_per_cell_ / 2.;
ogrid_.info.origin.orientation.w = 1;
ogrid_.data.resize(ogrid_.info.width * ogrid_.info.height);
ogrid_mat_ = cv::Mat(cv::Size(ogrid_.info.width, ogrid_.info.height), CV_8UC1, ogrid_.data.data());
Expand Down
4 changes: 2 additions & 2 deletions mil_common/ros_alarms/test/roscpp/heartbeat_monitor_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ TEST(HeartbeatMonitorTest, heartbeatMonitorTest)

// Publish heartbeat
ros::Publisher heartbeat_pub = nh.advertise<std_msgs::String>(heartbeat_topic, 1000);
auto pub_valid = [&heartbeat_pub](bool valid) { // Can publish a valid or invalid heartbeat
auto pub_valid = [&heartbeat_pub](bool valid) { // Can publish a valid or invalid heartbeat
std_msgs::String msg;
msg.data = (valid ? "Will pass the predicate" : ""); // second one won't
heartbeat_pub.publish(msg);
Expand Down Expand Up @@ -97,7 +97,7 @@ TEST(HeartbeatMonitorTest, heartbeatMonitorTest)
while (ros::Time::now() - hb_monitor.getLastBeatTime() < time_to_clear) // Shouldn't recover here,
{ // invalid heartbeat
sleep_until(time_to_raise * 0.8, ros::Time::now());
pub_valid(false); // False --> publish invalid heartbeat
pub_valid(false); // False --> publish invalid heartbeat
}
EXPECT_TRUE(listener.queryRaised());

Expand Down
2 changes: 1 addition & 1 deletion mil_common/ros_alarms/test/roscpp/listener_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ TEST(ListenerTest, listenerTest)
listener.addRaiseCb(raise_cb); // Use this overload for any severity raise
listener.addClearCb(clear_cb); // Called for any clear of the alarm

ros::Duration latency(0.01); // Approximate upper bound on publisher latency
ros::Duration latency(0.01); // Approximate upper bound on publisher latency
auto update_start = update_count;
auto lo_start = lo_priority_raise_count;
auto hi_start = hi_priority_raise_count;
Expand Down

0 comments on commit 3728f5c

Please sign in to comment.