Skip to content

Commit 0f1d92c

Browse files
modify cpp file to check clang-tidy
1 parent 19d5703 commit 0f1d92c

File tree

2 files changed

+23
-16
lines changed

2 files changed

+23
-16
lines changed

Diff for: fuse_models/include/fuse_models/unicycle_2d_ignition.hpp

+12-6
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,10 @@ class Unicycle2DIgnition : public fuse_core::AsyncSensorModel
9898
* All plugins are required to have a constructor that accepts no arguments
9999
*/
100100
Unicycle2DIgnition();
101+
Unicycle2DIgnition(Unicycle2DIgnition const&) = delete;
102+
Unicycle2DIgnition& operator=(Unicycle2DIgnition const&) = delete;
103+
Unicycle2DIgnition(Unicycle2DIgnition&&) = delete;
104+
Unicycle2DIgnition& operator=(Unicycle2DIgnition&&) = delete;
101105

102106
/**
103107
* @brief Destructor
@@ -140,15 +144,16 @@ class Unicycle2DIgnition : public fuse_core::AsyncSensorModel
140144
/**
141145
* @brief Triggers the publication of a new prior transaction at the supplied pose
142146
*/
143-
bool setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr service,
144-
std::shared_ptr<rmw_request_id_t>, const fuse_msgs::srv::SetPose::Request::SharedPtr req);
147+
bool setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr const& service,
148+
std::shared_ptr<rmw_request_id_t> const&,
149+
fuse_msgs::srv::SetPose::Request::SharedPtr const& req);
145150

146151
/**
147152
* @brief Triggers the publication of a new prior transaction at the supplied pose
148153
*/
149-
bool setPoseDeprecatedServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr service,
150-
std::shared_ptr<rmw_request_id_t> request_id,
151-
const fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr req);
154+
bool setPoseDeprecatedServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr const& service,
155+
std::shared_ptr<rmw_request_id_t> const& request_id,
156+
fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr const& req);
152157

153158
protected:
154159
/**
@@ -164,7 +169,8 @@ class Unicycle2DIgnition : public fuse_core::AsyncSensorModel
164169
*
165170
* @param[in] pose - The pose and covariance to use for the prior constraints on (x, y, yaw)
166171
*/
167-
void process(const geometry_msgs::msg::PoseWithCovarianceStamped& pose, std::function<void()> post_process = nullptr);
172+
void process(const geometry_msgs::msg::PoseWithCovarianceStamped& pose,
173+
std::function<void()> const& post_process = nullptr);
168174

169175
/**
170176
* @brief Create and send a prior transaction based on the supplied pose

Diff for: fuse_models/src/unicycle_2d_ignition.cpp

+11-10
Original file line numberDiff line numberDiff line change
@@ -161,9 +161,9 @@ void Unicycle2DIgnition::subscriberCallback(const geometry_msgs::msg::PoseWithCo
161161
}
162162
}
163163

164-
bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr service,
165-
std::shared_ptr<rmw_request_id_t> request_id,
166-
const fuse_msgs::srv::SetPose::Request::SharedPtr req)
164+
bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr const& service,
165+
std::shared_ptr<rmw_request_id_t> const& request_id,
166+
fuse_msgs::srv::SetPose::Request::SharedPtr const& req)
167167
{
168168
try
169169
{
@@ -185,8 +185,9 @@ bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::
185185
}
186186

187187
bool Unicycle2DIgnition::setPoseDeprecatedServiceCallback(
188-
rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr service, std::shared_ptr<rmw_request_id_t> request_id,
189-
const fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr req)
188+
rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr const& service,
189+
std::shared_ptr<rmw_request_id_t> const& request_id,
190+
fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr const& req)
190191
{
191192
try
192193
{
@@ -205,7 +206,7 @@ bool Unicycle2DIgnition::setPoseDeprecatedServiceCallback(
205206
}
206207

207208
void Unicycle2DIgnition::process(const geometry_msgs::msg::PoseWithCovarianceStamped& pose,
208-
std::function<void()> post_process)
209+
std::function<void()> const& post_process)
209210
{
210211
// Verify we are in the correct state to process set pose requests
211212
if (!started_)
@@ -219,10 +220,10 @@ void Unicycle2DIgnition::process(const geometry_msgs::msg::PoseWithCovarianceSta
219220
std::to_string(pose.pose.pose.position.x) + ", " +
220221
std::to_string(pose.pose.pose.position.y) + ").");
221222
}
222-
auto orientation_norm = std::sqrt(pose.pose.pose.orientation.x * pose.pose.pose.orientation.x +
223-
pose.pose.pose.orientation.y * pose.pose.pose.orientation.y +
224-
pose.pose.pose.orientation.z * pose.pose.pose.orientation.z +
225-
pose.pose.pose.orientation.w * pose.pose.pose.orientation.w);
223+
auto orientation_norm = std::sqrt((pose.pose.pose.orientation.x * pose.pose.pose.orientation.x) +
224+
(pose.pose.pose.orientation.y * pose.pose.pose.orientation.y) +
225+
(pose.pose.pose.orientation.z * pose.pose.pose.orientation.z) +
226+
(pose.pose.pose.orientation.w * pose.pose.pose.orientation.w));
226227
if (std::abs(orientation_norm - 1.0) > 1.0e-3)
227228
{
228229
throw std::invalid_argument(

0 commit comments

Comments
 (0)