Skip to content

Commit

Permalink
Applied "ament_clang_format" and passed cpplint, with manual adjustme…
Browse files Browse the repository at this point in the history
…nts made to the "include" order
  • Loading branch information
KuraZuzu committed Nov 20, 2024
1 parent 6c632e6 commit 2c1d411
Show file tree
Hide file tree
Showing 10 changed files with 138 additions and 196 deletions.
27 changes: 13 additions & 14 deletions include/raspimouse_ros2_examples/camera_line_follower_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,30 +50,29 @@ class CameraFollower : public rclcpp_lifecycle::LifecycleNode
cv::Point2d object_normalized_point_;
double object_normalized_area_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>> result_image_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>> cmd_vel_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
std::shared_ptr<rclcpp::Client<std_srvs::srv::SetBool>> motor_power_client_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
rclcpp::Subscription<raspimouse_msgs::msg::Switches>::SharedPtr switches_sub_;
rclcpp::TimerBase::SharedPtr cmd_vel_timer_;

void set_motor_power(const bool motor_on);
std::string mat_type2encoding(const int mat_type) const;
void convert_frame_to_message(
const cv::Mat & frame,
sensor_msgs::msg::Image & msg) const;
void convert_frame_to_message(const cv::Mat & frame, sensor_msgs::msg::Image & msg) const;

bool detect_line(const cv::Mat & input_frame, cv::Mat & result_frame);

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State &);
};

} // namespace camera_line_follower
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,7 @@ class PIDController
{
public:
PIDController()
: p_gain_(0.0), i_gain_(0.0), d_gain_(0.0),
error1_(0.0), error2_(0.0), output_(0.0)
: p_gain_(0.0), i_gain_(0.0), d_gain_(0.0), error1_(0.0), error2_(0.0), output_(0.0)
{
}

Expand Down
23 changes: 12 additions & 11 deletions include/raspimouse_ros2_examples/line_follower_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ class Follower : public rclcpp_lifecycle::LifecycleNode
bool can_publish_cmdvel_;

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Int16>> buzzer_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>> cmd_vel_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<raspimouse_msgs::msg::Leds>> leds_pub_;
rclcpp::Subscription<raspimouse_msgs::msg::LightSensors>::SharedPtr light_sensors_sub_;
rclcpp::Subscription<raspimouse_msgs::msg::Switches>::SharedPtr switches_sub_;
Expand All @@ -97,16 +98,16 @@ class Follower : public rclcpp_lifecycle::LifecycleNode
int median(const int value1, const int value2);
void set_line_thresholds(void);

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State &);
};

} // namespace line_follower
Expand Down
27 changes: 13 additions & 14 deletions include/raspimouse_ros2_examples/object_tracking_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,28 +48,27 @@ class Tracker : public rclcpp_lifecycle::LifecycleNode
double object_normalized_area_;
geometry_msgs::msg::TwistStamped cmd_vel_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>> result_image_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>> cmd_vel_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::TwistStamped>>
cmd_vel_pub_;
std::shared_ptr<rclcpp::Client<std_srvs::srv::SetBool>> motor_power_client_;
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
rclcpp::TimerBase::SharedPtr cmd_vel_timer_;

std::string mat_type2encoding(int mat_type);
void convert_frame_to_message(
const cv::Mat & frame,
sensor_msgs::msg::Image & msg);
void convert_frame_to_message(const cv::Mat & frame, sensor_msgs::msg::Image & msg);

void tracking(const cv::Mat & input_frame, cv::Mat & result_frame);

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_cleanup(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_shutdown(const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State &);
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State &);
};

} // namespace object_tracking
Expand Down
51 changes: 25 additions & 26 deletions include/raspimouse_ros2_examples/visibility_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,39 +16,38 @@
#define RASPIMOUSE_ROS2_EXAMPLES__VISIBILITY_CONTROL_H_

#ifdef __cplusplus
extern "C"
{
extern "C" {
#endif

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __attribute__ ((dllexport))
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT __attribute__ ((dllimport))
#else
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __declspec(dllexport)
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT __declspec(dllimport)
#endif
#ifdef RASPIMOUSE_ROS2_EXAMPLES_BUILDING_DLL
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC RASPIMOUSE_ROS2_EXAMPLES_EXPORT
#else
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC RASPIMOUSE_ROS2_EXAMPLES_IMPORT
#endif
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC_TYPE RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL
#ifdef __GNUC__
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __attribute__((dllexport))
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT __attribute__((dllimport))
#else
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __attribute__ ((visibility("default")))
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT
#if __GNUC__ >= 4
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC __attribute__ ((visibility("default")))
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL __attribute__ ((visibility("hidden")))
#else
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL
#endif
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC_TYPE
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __declspec(dllexport)
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT __declspec(dllimport)
#endif
#ifdef RASPIMOUSE_ROS2_EXAMPLES_BUILDING_DLL
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC RASPIMOUSE_ROS2_EXAMPLES_EXPORT
#else
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC RASPIMOUSE_ROS2_EXAMPLES_IMPORT
#endif
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC_TYPE RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL
#else
#define RASPIMOUSE_ROS2_EXAMPLES_EXPORT __attribute__((visibility("default")))
#define RASPIMOUSE_ROS2_EXAMPLES_IMPORT
#if __GNUC__ >= 4
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC __attribute__((visibility("default")))
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL __attribute__((visibility("hidden")))
#else
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
#define RASPIMOUSE_ROS2_EXAMPLES_LOCAL
#endif
#define RASPIMOUSE_ROS2_EXAMPLES_PUBLIC_TYPE
#endif

#ifdef __cplusplus
Expand Down
37 changes: 14 additions & 23 deletions src/camera_line_follower_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,7 @@ using namespace std::chrono_literals;
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

CameraFollower::CameraFollower(const rclcpp::NodeOptions & options)
: rclcpp_lifecycle::LifecycleNode("camera_follower", options),
object_is_detected_(false)
: rclcpp_lifecycle::LifecycleNode("camera_follower", options), object_is_detected_(false)
{
}

Expand Down Expand Up @@ -80,11 +79,12 @@ void CameraFollower::on_cmd_vel_timer()

// Follow the line
// when the number of pixels of the object is greater than the threshold.
if (object_is_detected_ &&
object_normalized_area_ > get_parameter(AREA_THRESHOLD_PARAM).as_double())
{
if (
object_is_detected_ &&
object_normalized_area_ > get_parameter(AREA_THRESHOLD_PARAM).as_double()) {
cmd_vel.twist.linear.x = get_parameter(LINEAR_VEL_PARAM).as_double();
cmd_vel.twist.angular.z = -get_parameter(ANGULAR_VEL_PARAM).as_double() * object_normalized_point_.x;
cmd_vel.twist.angular.z =
-get_parameter(ANGULAR_VEL_PARAM).as_double() * object_normalized_point_.x;
} else {
cmd_vel.twist.linear.x = 0.0;
cmd_vel.twist.angular.z = 0.0;
Expand All @@ -102,9 +102,7 @@ void CameraFollower::on_cmd_vel_timer()
void CameraFollower::set_motor_power(const bool motor_on)
{
if (motor_power_client_ == nullptr) {
RCLCPP_ERROR(
this->get_logger(),
"Service motor_power is not avaliable.");
RCLCPP_ERROR(this->get_logger(), "Service motor_power is not avaliable.");
return;
}
auto request = std::make_shared<std_srvs::srv::SetBool::Request>();
Expand Down Expand Up @@ -151,10 +149,8 @@ bool CameraFollower::detect_line(const cv::Mat & input_frame, cv::Mat & result_f
cv::cvtColor(input_frame, gray, cv::COLOR_BGR2GRAY);
cv::Mat extracted_bin;
cv::inRange(
gray,
get_parameter(MIN_BRIGHTNESS_PARAM).as_int(),
get_parameter(MAX_BRIGHTNESS_PARAM).as_int(),
extracted_bin);
gray, get_parameter(MIN_BRIGHTNESS_PARAM).as_int(),
get_parameter(MAX_BRIGHTNESS_PARAM).as_int(), extracted_bin);
input_frame.copyTo(result_frame, extracted_bin);

// Remove noise with morphology transformation
Expand Down Expand Up @@ -184,20 +180,17 @@ bool CameraFollower::detect_line(const cv::Mat & input_frame, cv::Mat & result_f

// Normalize the centroid coordinates to [-1.0, 1.0].
object_normalized_point_ = cv::Point2d(
2.0 * mt_point.x / input_frame.cols - 1.0,
2.0 * mt_point.y / input_frame.rows - 1.0
);
2.0 * mt_point.x / input_frame.cols - 1.0, 2.0 * mt_point.y / input_frame.rows - 1.0);
// Normalize the the contour area to [0.0, 1.0].
object_normalized_area_ = max_area / (input_frame.rows * input_frame.cols);

std::string text = "Area:" + std::to_string(object_normalized_area_ * 100) + "%";
cv::drawContours(
result_frame, contours, max_area_index,
cv::Scalar(0, 255, 0), 2, cv::LINE_4, hierarchy);
result_frame, contours, max_area_index, cv::Scalar(0, 255, 0), 2, cv::LINE_4, hierarchy);
cv::circle(result_frame, mt_point, 30, cv::Scalar(0, 0, 255), 2, cv::LINE_4);
cv::putText(
result_frame, text, cv::Point(0, 30),
cv::FONT_HERSHEY_SIMPLEX, 1, cv::Scalar(255, 255, 255), 2);
result_frame, text, cv::Point(0, 30), cv::FONT_HERSHEY_SIMPLEX, 1, cv::Scalar(255, 255, 255),
2);
return true;
} else {
return false;
Expand All @@ -214,9 +207,7 @@ CallbackReturn CameraFollower::on_configure(const rclcpp_lifecycle::State &)

motor_power_client_ = create_client<std_srvs::srv::SetBool>("motor_power");
if (!motor_power_client_->wait_for_service(5s)) {
RCLCPP_ERROR(
this->get_logger(),
"Service motor_power is not avaliable.");
RCLCPP_ERROR(this->get_logger(), "Service motor_power is not avaliable.");
return CallbackReturn::FAILURE;
}

Expand Down
24 changes: 7 additions & 17 deletions src/direction_controller_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,7 @@ enum CONTROL_MODE
MODE_ROTATION = 3
};

Controller::Controller(const rclcpp::NodeOptions & options)
: Node("direction_controller", options)
Controller::Controller(const rclcpp::NodeOptions & options) : Node("direction_controller", options)
{
using namespace std::placeholders; // for _1, _2, _3...

Expand Down Expand Up @@ -73,8 +72,7 @@ Controller::Controller(const rclcpp::NodeOptions & options)
this->declare_parameter("d_gain", 20.0, descriptor);

omega_pid_controller_.set_gain(
this->get_parameter("p_gain").as_double(),
this->get_parameter("i_gain").as_double(),
this->get_parameter("p_gain").as_double(), this->get_parameter("i_gain").as_double(),
this->get_parameter("d_gain").as_double());

pressed_switch_number_ = -1;
Expand Down Expand Up @@ -104,8 +102,7 @@ void Controller::on_cmd_vel_timer()
}

omega_pid_controller_.set_gain(
this->get_parameter("p_gain").as_double(),
this->get_parameter("i_gain").as_double(),
this->get_parameter("p_gain").as_double(), this->get_parameter("i_gain").as_double(),
this->get_parameter("d_gain").as_double());

if (released_switch_number != -1 || filtered_acc_.z > 0.0) {
Expand Down Expand Up @@ -170,9 +167,7 @@ void Controller::callback_imu_data_raw(const sensor_msgs::msg::Imu::SharedPtr ms
bool Controller::set_motor_power(const bool motor_on)
{
if (!motor_power_client_->wait_for_service(5s)) {
RCLCPP_ERROR(
this->get_logger(),
"Service motor_power is not avaliable.");
RCLCPP_ERROR(this->get_logger(), "Service motor_power is not avaliable.");
return false;
}
auto request = std::make_shared<std_srvs::srv::SetBool::Request>();
Expand All @@ -189,9 +184,8 @@ bool Controller::omega_calibration(const double omega)
omega_samples_.push_back(omega);

if (omega_samples_.size() >= SAMPLE_NUM) {
omega_bias_ = std::accumulate(
std::begin(omega_samples_),
std::end(omega_samples_), 0.0) / omega_samples_.size();
omega_bias_ = std::accumulate(std::begin(omega_samples_), std::end(omega_samples_), 0.0) /
omega_samples_.size();
omega_samples_.clear();
complete = true;
}
Expand Down Expand Up @@ -267,10 +261,7 @@ void Controller::beep_buzzer(const int freq, const std::chrono::nanoseconds & be
buzzer_pub_->publish(std::move(msg));
}

void Controller::beep_start(void)
{
beep_buzzer(1000, 500ms);
}
void Controller::beep_start(void) { beep_buzzer(1000, 500ms); }

void Controller::beep_success(void)
{
Expand All @@ -287,7 +278,6 @@ void Controller::beep_failure(void)
}
}


} // namespace direction_controller

#include "rclcpp_components/register_node_macro.hpp"
Expand Down
Loading

0 comments on commit 2c1d411

Please sign in to comment.