Skip to content

Commit

Permalink
Revert "Adapt clang-format with Google style"
Browse files Browse the repository at this point in the history
This reverts commit 0a42043.
  • Loading branch information
KuraZuzu committed Nov 20, 2024
1 parent 8797078 commit 304f82b
Show file tree
Hide file tree
Showing 12 changed files with 476 additions and 402 deletions.
34 changes: 17 additions & 17 deletions include/raspimouse_ros2_examples/camera_line_follower_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,51 +18,51 @@
#include <memory>
#include <string>

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "raspimouse_msgs/msg/switches.hpp"
#include "raspimouse_ros2_examples/visibility_control.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "opencv2/highgui/highgui.hpp"

namespace camera_line_follower {
namespace camera_line_follower
{

class CameraFollower : public rclcpp_lifecycle::LifecycleNode {
public:
class CameraFollower : public rclcpp_lifecycle::LifecycleNode
{
public:
RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
explicit CameraFollower(const rclcpp::NodeOptions &options);
explicit CameraFollower(const rclcpp::NodeOptions & options);

protected:
protected:
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg_image);
void callback_switches(const raspimouse_msgs::msg::Switches::SharedPtr msg);
void on_cmd_vel_timer();

private:
private:
cv::VideoCapture cap_;
bool object_is_detected_;
bool enable_following_;
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<sensor_msgs::msg::Image>> result_image_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);
bool detect_line(const cv::Mat & input_frame, cv::Mat & result_frame);

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &);
Expand Down
52 changes: 28 additions & 24 deletions include/raspimouse_ros2_examples/direction_controller_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,30 +19,31 @@
#include <string>
#include <vector>

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "geometry_msgs/msg/vector3.hpp"
#include "raspimouse_msgs/msg/switches.hpp"
#include "raspimouse_ros2_examples/visibility_control.h"
#include "raspimouse_msgs/msg/switches.hpp"
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "std_msgs/msg/float64.hpp"
#include "std_msgs/msg/int16.hpp"
#include "std_msgs/msg/float64.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "geometry_msgs/msg/vector3.hpp"

namespace direction_controller {
namespace direction_controller
{

class PIDController {
public:
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) {}

double update(const double current, const double target) {
: p_gain_(0.0), i_gain_(0.0), d_gain_(0.0),
error1_(0.0), error2_(0.0), output_(0.0)
{
}

double update(const double current, const double target)
{
double error = target - current;

double delta_output = p_gain_ * (error - error1_);
Expand All @@ -57,19 +58,21 @@ class PIDController {
return output_;
}

void set_gain(const double p_gain, const double i_gain, const double d_gain) {
void set_gain(const double p_gain, const double i_gain, const double d_gain)
{
p_gain_ = p_gain;
i_gain_ = i_gain;
d_gain_ = d_gain;
}

void reset_output_and_errors() {
void reset_output_and_errors()
{
error1_ = 0.0;
error2_ = 0.0;
output_ = 0.0;
}

private:
private:
double p_gain_;
double i_gain_;
double d_gain_;
Expand All @@ -78,15 +81,16 @@ class PIDController {
double output_;
};

class Controller : public rclcpp::Node {
public:
class Controller : public rclcpp::Node
{
public:
RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
explicit Controller(const rclcpp::NodeOptions& options);
explicit Controller(const rclcpp::NodeOptions & options);

protected:
protected:
void on_cmd_vel_timer();

private:
private:
raspimouse_msgs::msg::Switches switches_;
sensor_msgs::msg::Imu imu_data_raw_;

Expand Down Expand Up @@ -120,7 +124,7 @@ class Controller : public rclcpp::Node {
void calculate_heading_angle(const double omega, const double current_time);
void angle_control(const double target_angle);
void rotation(void);
void beep_buzzer(const int freq, const std::chrono::nanoseconds& beep_time);
void beep_buzzer(const int freq, const std::chrono::nanoseconds & beep_time);
void beep_start(void);
void beep_success(void);
void beep_failure(void);
Expand Down
50 changes: 26 additions & 24 deletions include/raspimouse_ros2_examples/line_follower_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,32 +19,41 @@
#include <string>
#include <vector>

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "raspimouse_msgs/msg/leds.hpp"
#include "raspimouse_msgs/msg/light_sensors.hpp"
#include "raspimouse_msgs/msg/switches.hpp"
#include "raspimouse_ros2_examples/visibility_control.h"
#include "raspimouse_msgs/msg/switches.hpp"
#include "raspimouse_msgs/msg/light_sensors.hpp"
#include "raspimouse_msgs/msg/leds.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "std_msgs/msg/int16.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"

namespace line_follower {
namespace line_follower
{

class Follower : public rclcpp_lifecycle::LifecycleNode {
public:
class Follower : public rclcpp_lifecycle::LifecycleNode
{
public:
RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
explicit Follower(const rclcpp::NodeOptions &options);
explicit Follower(const rclcpp::NodeOptions & options);

protected:
protected:
void on_cmd_vel_timer();

private:
private:
using SensorsType = std::vector<int>;

enum SensorIndex { LEFT = 0, MID_LEFT, MID_RIGHT, RIGHT, SENSOR_NUM };
enum SensorIndex
{
LEFT = 0,
MID_LEFT,
MID_RIGHT,
RIGHT,
SENSOR_NUM
};

static const int NUM_OF_SAMPLES;

Expand All @@ -62,31 +71,24 @@ class Follower : public rclcpp_lifecycle::LifecycleNode {
bool field_sampling_;
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<raspimouse_msgs::msg::Leds>>
leds_pub_;
rclcpp::Subscription<raspimouse_msgs::msg::LightSensors>::SharedPtr
light_sensors_sub_;
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<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_;
std::shared_ptr<rclcpp::Client<std_srvs::srv::SetBool>> motor_power_client_;

rclcpp::TimerBase::SharedPtr cmd_vel_timer_;

void callback_light_sensors(
const raspimouse_msgs::msg::LightSensors::SharedPtr msg);
void callback_light_sensors(const raspimouse_msgs::msg::LightSensors::SharedPtr msg);
void callback_switches(const raspimouse_msgs::msg::Switches::SharedPtr msg);

void set_motor_power(const bool motor_on);
void publish_cmdvel_for_line_following(void);
void update_line_detection(void);
bool line_is_bright(void);
void indicate_line_detections(void);
void beep_buzzer(const int freq, const std::chrono::nanoseconds &beep_time);
void beep_buzzer(const int freq, const std::chrono::nanoseconds & beep_time);
void beep_start(void);
void beep_success(void);
void beep_failure(void);
Expand Down
34 changes: 17 additions & 17 deletions include/raspimouse_ros2_examples/object_tracking_component.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,47 +18,47 @@
#include <memory>
#include <string>

#include "geometry_msgs/msg/twist_stamped.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "raspimouse_ros2_examples/visibility_control.h"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "opencv2/highgui/highgui.hpp"

namespace object_tracking {
namespace object_tracking
{

class Tracker : public rclcpp_lifecycle::LifecycleNode {
public:
class Tracker : public rclcpp_lifecycle::LifecycleNode
{
public:
RASPIMOUSE_ROS2_EXAMPLES_PUBLIC
explicit Tracker(const rclcpp::NodeOptions &options);
explicit Tracker(const rclcpp::NodeOptions & options);

protected:
protected:
void image_callback(const sensor_msgs::msg::Image::SharedPtr msg_image);
void on_cmd_vel_timer();

private:
private:
cv::VideoCapture cap_;
bool object_is_detected_;
cv::Point2d object_normalized_point_;
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<sensor_msgs::msg::Image>> result_image_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);
void tracking(const cv::Mat & input_frame, cv::Mat & result_frame);

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_configure(const rclcpp_lifecycle::State &);
Expand Down
51 changes: 26 additions & 25 deletions include/raspimouse_ros2_examples/visibility_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,38 +16,39 @@
#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))
#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
#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
#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 __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
Loading

0 comments on commit 304f82b

Please sign in to comment.