Skip to content

Commit

Permalink
modify cpp file to check clang-tidy
Browse files Browse the repository at this point in the history
  • Loading branch information
henrygerardmoore committed Feb 14, 2025
1 parent 19d5703 commit 0f1d92c
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 16 deletions.
18 changes: 12 additions & 6 deletions fuse_models/include/fuse_models/unicycle_2d_ignition.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,10 @@ class Unicycle2DIgnition : public fuse_core::AsyncSensorModel
* All plugins are required to have a constructor that accepts no arguments
*/
Unicycle2DIgnition();
Unicycle2DIgnition(Unicycle2DIgnition const&) = delete;
Unicycle2DIgnition& operator=(Unicycle2DIgnition const&) = delete;
Unicycle2DIgnition(Unicycle2DIgnition&&) = delete;
Unicycle2DIgnition& operator=(Unicycle2DIgnition&&) = delete;

/**
* @brief Destructor
Expand Down Expand Up @@ -140,15 +144,16 @@ class Unicycle2DIgnition : public fuse_core::AsyncSensorModel
/**
* @brief Triggers the publication of a new prior transaction at the supplied pose
*/
bool setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr service,
std::shared_ptr<rmw_request_id_t>, const fuse_msgs::srv::SetPose::Request::SharedPtr req);
bool setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr const& service,
std::shared_ptr<rmw_request_id_t> const&,
fuse_msgs::srv::SetPose::Request::SharedPtr const& req);

/**
* @brief Triggers the publication of a new prior transaction at the supplied pose
*/
bool setPoseDeprecatedServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr service,
std::shared_ptr<rmw_request_id_t> request_id,
const fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr req);
bool setPoseDeprecatedServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr const& service,
std::shared_ptr<rmw_request_id_t> const& request_id,
fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr const& req);

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

/**
* @brief Create and send a prior transaction based on the supplied pose
Expand Down
21 changes: 11 additions & 10 deletions fuse_models/src/unicycle_2d_ignition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,9 +161,9 @@ void Unicycle2DIgnition::subscriberCallback(const geometry_msgs::msg::PoseWithCo
}
}

bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr service,
std::shared_ptr<rmw_request_id_t> request_id,
const fuse_msgs::srv::SetPose::Request::SharedPtr req)
bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::SetPose>::SharedPtr const& service,
std::shared_ptr<rmw_request_id_t> const& request_id,
fuse_msgs::srv::SetPose::Request::SharedPtr const& req)
{
try
{
Expand All @@ -185,8 +185,9 @@ bool Unicycle2DIgnition::setPoseServiceCallback(rclcpp::Service<fuse_msgs::srv::
}

bool Unicycle2DIgnition::setPoseDeprecatedServiceCallback(
rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr service, std::shared_ptr<rmw_request_id_t> request_id,
const fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr req)
rclcpp::Service<fuse_msgs::srv::SetPoseDeprecated>::SharedPtr const& service,
std::shared_ptr<rmw_request_id_t> const& request_id,
fuse_msgs::srv::SetPoseDeprecated::Request::SharedPtr const& req)
{
try
{
Expand All @@ -205,7 +206,7 @@ bool Unicycle2DIgnition::setPoseDeprecatedServiceCallback(
}

void Unicycle2DIgnition::process(const geometry_msgs::msg::PoseWithCovarianceStamped& pose,
std::function<void()> post_process)
std::function<void()> const& post_process)
{
// Verify we are in the correct state to process set pose requests
if (!started_)
Expand All @@ -219,10 +220,10 @@ void Unicycle2DIgnition::process(const geometry_msgs::msg::PoseWithCovarianceSta
std::to_string(pose.pose.pose.position.x) + ", " +
std::to_string(pose.pose.pose.position.y) + ").");
}
auto orientation_norm = std::sqrt(pose.pose.pose.orientation.x * pose.pose.pose.orientation.x +
pose.pose.pose.orientation.y * pose.pose.pose.orientation.y +
pose.pose.pose.orientation.z * pose.pose.pose.orientation.z +
pose.pose.pose.orientation.w * pose.pose.pose.orientation.w);
auto orientation_norm = std::sqrt((pose.pose.pose.orientation.x * pose.pose.pose.orientation.x) +
(pose.pose.pose.orientation.y * pose.pose.pose.orientation.y) +
(pose.pose.pose.orientation.z * pose.pose.pose.orientation.z) +
(pose.pose.pose.orientation.w * pose.pose.pose.orientation.w));
if (std::abs(orientation_norm - 1.0) > 1.0e-3)
{
throw std::invalid_argument(
Expand Down

0 comments on commit 0f1d92c

Please sign in to comment.