Skip to content

Commit

Permalink
Apply reformat
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar committed Aug 25, 2021
1 parent 8b570e7 commit 3400a9a
Show file tree
Hide file tree
Showing 69 changed files with 1,812 additions and 1,933 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@
#include "diff_drive_controller/odometry.hpp"
#include "diff_drive_controller/speed_limiter.hpp"
#include "diff_drive_controller/visibility_control.h"
#include "hardware_interface/handle.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "hardware_interface/handle.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "odometry.hpp"
#include "rclcpp/rclcpp.hpp"
Expand All @@ -42,7 +42,6 @@
#include "realtime_tools/realtime_publisher.h"
#include "tf2_msgs/msg/tf_message.hpp"


namespace diff_drive_controller
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
Expand All @@ -56,16 +55,13 @@ class DiffDriveController : public controller_interface::ControllerInterface
DiffDriveController();

DIFF_DRIVE_CONTROLLER_PUBLIC
controller_interface::return_type
init(const std::string & controller_name) override;
controller_interface::return_type init(const std::string & controller_name) override;

DIFF_DRIVE_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration
command_interface_configuration() const override;
controller_interface::InterfaceConfiguration command_interface_configuration() const override;

DIFF_DRIVE_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration
state_interface_configuration() const override;
controller_interface::InterfaceConfiguration state_interface_configuration() const override;

DIFF_DRIVE_CONTROLLER_PUBLIC
controller_interface::return_type update() override;
Expand Down Expand Up @@ -96,8 +92,7 @@ class DiffDriveController : public controller_interface::ControllerInterface
};

CallbackReturn configure_side(
const std::string & side,
const std::vector<std::string> & wheel_names,
const std::string & side, const std::vector<std::string> & wheel_names,
std::vector<WheelHandle> & registered_handles);

std::vector<std::string> left_wheel_names_;
Expand All @@ -109,8 +104,8 @@ class DiffDriveController : public controller_interface::ControllerInterface
struct WheelParams
{
size_t wheels_per_side = 0;
double separation = 0.0; // w.r.t. the midpoint of the wheel width
double radius = 0.0; // Assumed to be the same for both wheels
double separation = 0.0; // w.r.t. the midpoint of the wheel width
double radius = 0.0; // Assumed to be the same for both wheels
double separation_multiplier = 1.0;
double left_radius_multiplier = 1.0;
double right_radius_multiplier = 1.0;
Expand All @@ -130,21 +125,20 @@ class DiffDriveController : public controller_interface::ControllerInterface

std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::Odometry>> odometry_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::msg::Odometry>>
realtime_odometry_publisher_ = nullptr;
realtime_odometry_publisher_ = nullptr;

std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>>
odometry_transform_publisher_ = nullptr;
std::shared_ptr<rclcpp::Publisher<tf2_msgs::msg::TFMessage>> odometry_transform_publisher_ =
nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<tf2_msgs::msg::TFMessage>>
realtime_odometry_transform_publisher_ = nullptr;
realtime_odometry_transform_publisher_ = nullptr;

// Timeout to consider cmd_vel commands old
std::chrono::milliseconds cmd_vel_timeout_{500};

bool subscriber_is_active_ = false;
rclcpp::Subscription<Twist>::SharedPtr velocity_command_subscriber_ = nullptr;
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr velocity_command_unstamped_subscriber_
=
nullptr;
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr
velocity_command_unstamped_subscriber_ = nullptr;

realtime_tools::RealtimeBox<std::shared_ptr<Twist>> received_velocity_msg_ptr_{nullptr};

Expand All @@ -155,10 +149,9 @@ class DiffDriveController : public controller_interface::ControllerInterface
SpeedLimiter limiter_angular_;

bool publish_limited_velocity_ = false;
std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ =
std::shared_ptr<rclcpp::Publisher<Twist>> limited_velocity_publisher_ = nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<Twist>> realtime_limited_velocity_publisher_ =
nullptr;
std::shared_ptr<realtime_tools::RealtimePublisher<Twist>>
realtime_limited_velocity_publisher_ = nullptr;

rclcpp::Time previous_update_timestamp_{0};

Expand Down
29 changes: 6 additions & 23 deletions diff_drive_controller/include/diff_drive_controller/odometry.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@

namespace diff_drive_controller
{

class Odometry
{
public:
Expand All @@ -40,33 +39,17 @@ class Odometry
void updateOpenLoop(double linear, double angular, const rclcpp::Time & time);
void resetOdometry();

double getX() const
{
return x_;
}
double getY() const
{
return y_;
}
double getHeading() const
{
return heading_;
}
double getLinear() const
{
return linear_;
}
double getAngular() const
{
return angular_;
}
double getX() const { return x_; }
double getY() const { return y_; }
double getHeading() const { return heading_; }
double getLinear() const { return linear_; }
double getAngular() const { return angular_; }

void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius);
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size);

private:
using RollingMeanAccumulator =
diff_drive_controller::RollingMeanAccumulator<double>;
using RollingMeanAccumulator = diff_drive_controller::RollingMeanAccumulator<double>;

void integrateRungeKutta2(double linear, double angular);
void integrateExact(double linear, double angular);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,20 +24,18 @@

namespace diff_drive_controller
{

/**
* \brief Simplification of boost::accumulators::accumulator_set<double,
* bacc::stats<bacc::tag::rolling_mean>> to avoid dragging boost dependencies
*
* Computes the mean of the last accumulated elements
*/
template<typename T>
template <typename T>
class RollingMeanAccumulator
{
public:
explicit RollingMeanAccumulator(size_t rolling_window_size)
: buffer_(rolling_window_size, 0.0), next_insert_(0),
sum_(0.0), buffer_filled_(false)
: buffer_(rolling_window_size, 0.0), next_insert_(0), sum_(0.0), buffer_filled_(false)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,9 @@ class SpeedLimiter
*/
SpeedLimiter(
bool has_velocity_limits = false, bool has_acceleration_limits = false,
bool has_jerk_limits = false,
double min_velocity = NAN, double max_velocity = NAN, double min_acceleration = NAN,
double max_acceleration = NAN, double min_jerk = NAN, double max_jerk = NAN);
bool has_jerk_limits = false, double min_velocity = NAN, double max_velocity = NAN,
double min_acceleration = NAN, double max_acceleration = NAN, double min_jerk = NAN,
double max_jerk = NAN);

/**
* \brief Limit the velocity and acceleration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,31 +26,31 @@
// https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define DIFF_DRIVE_CONTROLLER_EXPORT __attribute__ ((dllexport))
#define DIFF_DRIVE_CONTROLLER_IMPORT __attribute__ ((dllimport))
#else
#define DIFF_DRIVE_CONTROLLER_EXPORT __declspec(dllexport)
#define DIFF_DRIVE_CONTROLLER_IMPORT __declspec(dllimport)
#endif
#ifdef DIFF_DRIVE_CONTROLLER_BUILDING_DLL
#define DIFF_DRIVE_CONTROLLER_PUBLIC DIFF_DRIVE_CONTROLLER_EXPORT
#else
#define DIFF_DRIVE_CONTROLLER_PUBLIC DIFF_DRIVE_CONTROLLER_IMPORT
#endif
#define DIFF_DRIVE_CONTROLLER_PUBLIC_TYPE DIFF_DRIVE_CONTROLLER_PUBLIC
#define DIFF_DRIVE_CONTROLLER_LOCAL
#ifdef __GNUC__
#define DIFF_DRIVE_CONTROLLER_EXPORT __attribute__((dllexport))
#define DIFF_DRIVE_CONTROLLER_IMPORT __attribute__((dllimport))
#else
#define DIFF_DRIVE_CONTROLLER_EXPORT __attribute__ ((visibility("default")))
#define DIFF_DRIVE_CONTROLLER_IMPORT
#if __GNUC__ >= 4
#define DIFF_DRIVE_CONTROLLER_PUBLIC __attribute__ ((visibility("default")))
#define DIFF_DRIVE_CONTROLLER_LOCAL __attribute__ ((visibility("hidden")))
#else
#define DIFF_DRIVE_CONTROLLER_PUBLIC
#define DIFF_DRIVE_CONTROLLER_LOCAL
#endif
#define DIFF_DRIVE_CONTROLLER_PUBLIC_TYPE
#define DIFF_DRIVE_CONTROLLER_EXPORT __declspec(dllexport)
#define DIFF_DRIVE_CONTROLLER_IMPORT __declspec(dllimport)
#endif
#ifdef DIFF_DRIVE_CONTROLLER_BUILDING_DLL
#define DIFF_DRIVE_CONTROLLER_PUBLIC DIFF_DRIVE_CONTROLLER_EXPORT
#else
#define DIFF_DRIVE_CONTROLLER_PUBLIC DIFF_DRIVE_CONTROLLER_IMPORT
#endif
#define DIFF_DRIVE_CONTROLLER_PUBLIC_TYPE DIFF_DRIVE_CONTROLLER_PUBLIC
#define DIFF_DRIVE_CONTROLLER_LOCAL
#else
#define DIFF_DRIVE_CONTROLLER_EXPORT __attribute__((visibility("default")))
#define DIFF_DRIVE_CONTROLLER_IMPORT
#if __GNUC__ >= 4
#define DIFF_DRIVE_CONTROLLER_PUBLIC __attribute__((visibility("default")))
#define DIFF_DRIVE_CONTROLLER_LOCAL __attribute__((visibility("hidden")))
#else
#define DIFF_DRIVE_CONTROLLER_PUBLIC
#define DIFF_DRIVE_CONTROLLER_LOCAL
#endif
#define DIFF_DRIVE_CONTROLLER_PUBLIC_TYPE
#endif

#endif // DIFF_DRIVE_CONTROLLER__VISIBILITY_CONTROL_H_
Loading

0 comments on commit 3400a9a

Please sign in to comment.