Skip to content

Commit

Permalink
Enable uncrustify and cpplint.
Browse files Browse the repository at this point in the history
And fix all of the style issues that arose out of that.
No functional change, style only.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jun 2, 2022
1 parent c5c26b7 commit 1ca5533
Show file tree
Hide file tree
Showing 4 changed files with 113 additions and 135 deletions.
2 changes: 0 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,6 @@ install(DIRECTORY launch config
if(BUILD_TESTING)
# Disable some broken tests for now
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
set(ament_cmake_uncrustify_FOUND TRUE)

find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
12 changes: 6 additions & 6 deletions include/teleop_twist_joy/teleop_twist_joy.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCL
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef TELEOP_TWIST_JOY_TELEOP_TWIST_JOY_H
#define TELEOP_TWIST_JOY_TELEOP_TWIST_JOY_H
#ifndef TELEOP_TWIST_JOY__TELEOP_TWIST_JOY_HPP_
#define TELEOP_TWIST_JOY__TELEOP_TWIST_JOY_HPP_

#include <rclcpp/rclcpp.hpp>
#include "teleop_twist_joy/teleop_twist_joy_export.h"
Expand All @@ -37,16 +37,16 @@ namespace teleop_twist_joy
class TELEOP_TWIST_JOY_EXPORT TeleopTwistJoy : public rclcpp::Node
{
public:
explicit TeleopTwistJoy(const rclcpp::NodeOptions& options);
explicit TeleopTwistJoy(const rclcpp::NodeOptions & options);

virtual ~TeleopTwistJoy();

private:
struct Impl;
Impl* pimpl_;
OnSetParametersCallbackHandle::SharedPtr callback_handle;
Impl * pimpl_;
OnSetParametersCallbackHandle::SharedPtr callback_handle;
};

} // namespace teleop_twist_joy

#endif // TELEOP_TWIST_JOY_TELEOP_TWIST_JOY_H
#endif // TELEOP_TWIST_JOY__TELEOP_TWIST_JOY_HPP_
2 changes: 1 addition & 1 deletion src/teleop_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI

#include "teleop_twist_joy/teleop_twist_joy.hpp"

int main(int argc, char *argv[])
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

Expand Down
232 changes: 106 additions & 126 deletions src/teleop_twist_joy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,11 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
#include <set>
#include <string>

#include "rcutils/logging_macros.h"

#include <geometry_msgs/msg/twist.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>
#include <rcutils/logging_macros.h>
#include <sensor_msgs/msg/joy.hpp>

#include "teleop_twist_joy/teleop_twist_joy.hpp"
Expand All @@ -51,7 +52,7 @@ namespace teleop_twist_joy
struct TeleopTwistJoy::Impl
{
void joyCallback(const sensor_msgs::msg::Joy::SharedPtr joy);
void sendCmdVelMsg(const sensor_msgs::msg::Joy::SharedPtr, const std::string& which_map);
void sendCmdVelMsg(const sensor_msgs::msg::Joy::SharedPtr, const std::string & which_map);

rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr joy_sub;
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub;
Expand All @@ -72,12 +73,14 @@ struct TeleopTwistJoy::Impl
/**
* Constructs TeleopTwistJoy.
*/
TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions& options) : Node("teleop_twist_joy_node", options)
TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions & options)
: rclcpp::Node("teleop_twist_joy_node", options)
{
pimpl_ = new Impl;

pimpl_->cmd_vel_pub = this->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 10);
pimpl_->joy_sub = this->create_subscription<sensor_msgs::msg::Joy>("joy", rclcpp::QoS(10),
pimpl_->joy_sub = this->create_subscription<sensor_msgs::msg::Joy>(
"joy", rclcpp::QoS(10),
std::bind(&TeleopTwistJoy::Impl::joyCallback, this->pimpl_, std::placeholders::_1));

pimpl_->require_enable_button = this->declare_parameter("require_enable_button", true);
Expand Down Expand Up @@ -134,127 +137,106 @@ TeleopTwistJoy::TeleopTwistJoy(const rclcpp::NodeOptions& options) : Node("teleo
this->declare_parameters("scale_angular_turbo", default_scale_angular_turbo_map);
this->get_parameters("scale_angular_turbo", pimpl_->scale_angular_map["turbo"]);

ROS_INFO_COND_NAMED(pimpl_->require_enable_button, "TeleopTwistJoy",
"Teleop enable button %" PRId64 ".", pimpl_->enable_button);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
ROS_INFO_COND_NAMED(
pimpl_->require_enable_button, "TeleopTwistJoy",
"Teleop enable button %" PRId64 ".", pimpl_->enable_button);
ROS_INFO_COND_NAMED(
pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
"Turbo on button %" PRId64 ".", pimpl_->enable_turbo_button);

for (std::map<std::string, int64_t>::iterator it = pimpl_->axis_linear_map.begin();
it != pimpl_->axis_linear_map.end(); ++it)
it != pimpl_->axis_linear_map.end(); ++it)
{
ROS_INFO_COND_NAMED(it->second != -1L, "TeleopTwistJoy", "Linear axis %s on %" PRId64 " at scale %f.",
ROS_INFO_COND_NAMED(
it->second != -1L, "TeleopTwistJoy", "Linear axis %s on %" PRId64 " at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_linear_map["normal"][it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0 && it->second != -1, "TeleopTwistJoy",
"Turbo for linear axis %s is scale %f.", it->first.c_str(), pimpl_->scale_linear_map["turbo"][it->first]);
ROS_INFO_COND_NAMED(
pimpl_->enable_turbo_button >= 0 && it->second != -1, "TeleopTwistJoy",
"Turbo for linear axis %s is scale %f.", it->first.c_str(),
pimpl_->scale_linear_map["turbo"][it->first]);
}

for (std::map<std::string, int64_t>::iterator it = pimpl_->axis_angular_map.begin();
it != pimpl_->axis_angular_map.end(); ++it)
it != pimpl_->axis_angular_map.end(); ++it)
{
ROS_INFO_COND_NAMED(it->second != -1L, "TeleopTwistJoy", "Angular axis %s on %" PRId64 " at scale %f.",
ROS_INFO_COND_NAMED(
it->second != -1L, "TeleopTwistJoy", "Angular axis %s on %" PRId64 " at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_angular_map["normal"][it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0 && it->second != -1, "TeleopTwistJoy",
"Turbo for angular axis %s is scale %f.", it->first.c_str(), pimpl_->scale_angular_map["turbo"][it->first]);
ROS_INFO_COND_NAMED(
pimpl_->enable_turbo_button >= 0 && it->second != -1, "TeleopTwistJoy",
"Turbo for angular axis %s is scale %f.", it->first.c_str(),
pimpl_->scale_angular_map["turbo"][it->first]);
}

pimpl_->sent_disable_msg = false;

auto param_callback =
[this](std::vector<rclcpp::Parameter> parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;

// Loop to assign changed parameters to the member variables
for (const auto & parameter : parameters)
[this](std::vector<rclcpp::Parameter> parameters)
{
if (parameter.get_name() == "require_enable_button")
{
this->pimpl_->require_enable_button = parameter.get_value<rclcpp::PARAMETER_BOOL>();
}
if (parameter.get_name() == "enable_button")
{
this->pimpl_->enable_button = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "enable_turbo_button")
{
this->pimpl_->enable_turbo_button = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_linear.x")
{
this->pimpl_->axis_linear_map["x"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_linear.y")
{
this->pimpl_->axis_linear_map["y"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_linear.z")
{
this->pimpl_->axis_linear_map["z"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_angular.yaw")
{
this->pimpl_->axis_angular_map["yaw"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_angular.pitch")
{
this->pimpl_->axis_angular_map["pitch"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "axis_angular.roll")
{
this->pimpl_->axis_angular_map["roll"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
}
else if (parameter.get_name() == "scale_linear_turbo.x")
{
this->pimpl_->scale_linear_map["turbo"]["x"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_linear_turbo.y")
{
this->pimpl_->scale_linear_map["turbo"]["y"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_linear_turbo.z")
{
this->pimpl_->scale_linear_map["turbo"]["z"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_linear.x")
{
this->pimpl_->scale_linear_map["normal"]["x"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;

// Loop to assign changed parameters to the member variables
for (const auto & parameter : parameters) {
if (parameter.get_name() == "require_enable_button") {
this->pimpl_->require_enable_button = parameter.get_value<rclcpp::PARAMETER_BOOL>();
} else if (parameter.get_name() == "enable_button") {
this->pimpl_->enable_button = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "enable_turbo_button") {
this->pimpl_->enable_turbo_button = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_linear.x") {
this->pimpl_->axis_linear_map["x"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_linear.y") {
this->pimpl_->axis_linear_map["y"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_linear.z") {
this->pimpl_->axis_linear_map["z"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_angular.yaw") {
this->pimpl_->axis_angular_map["yaw"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_angular.pitch") {
this->pimpl_->axis_angular_map["pitch"] =
parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "axis_angular.roll") {
this->pimpl_->axis_angular_map["roll"] = parameter.get_value<rclcpp::PARAMETER_INTEGER>();
} else if (parameter.get_name() == "scale_linear_turbo.x") {
this->pimpl_->scale_linear_map["turbo"]["x"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_linear_turbo.y") {
this->pimpl_->scale_linear_map["turbo"]["y"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_linear_turbo.z") {
this->pimpl_->scale_linear_map["turbo"]["z"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_linear.x") {
this->pimpl_->scale_linear_map["normal"]["x"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_linear.y") {
this->pimpl_->scale_linear_map["normal"]["y"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_linear.z") {
this->pimpl_->scale_linear_map["normal"]["z"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular_turbo.yaw") {
this->pimpl_->scale_angular_map["turbo"]["yaw"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular_turbo.pitch") {
this->pimpl_->scale_angular_map["turbo"]["pitch"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular_turbo.roll") {
this->pimpl_->scale_angular_map["turbo"]["roll"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular.yaw") {
this->pimpl_->scale_angular_map["normal"]["yaw"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular.pitch") {
this->pimpl_->scale_angular_map["normal"]["pitch"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
} else if (parameter.get_name() == "scale_angular.roll") {
this->pimpl_->scale_angular_map["normal"]["roll"] =
parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
}
else if (parameter.get_name() == "scale_linear.y")
{
this->pimpl_->scale_linear_map["normal"]["y"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_linear.z")
{
this->pimpl_->scale_linear_map["normal"]["z"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular_turbo.yaw")
{
this->pimpl_->scale_angular_map["turbo"]["yaw"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular_turbo.pitch")
{
this->pimpl_->scale_angular_map["turbo"]["pitch"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular_turbo.roll")
{
this->pimpl_->scale_angular_map["turbo"]["roll"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular.yaw")
{
this->pimpl_->scale_angular_map["normal"]["yaw"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular.pitch")
{
this->pimpl_->scale_angular_map["normal"]["pitch"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
else if (parameter.get_name() == "scale_angular.roll")
{
this->pimpl_->scale_angular_map["normal"]["roll"] = parameter.get_value<rclcpp::PARAMETER_DOUBLE>();
}
}
return result;
};
return result;
};

callback_handle = this->add_on_set_parameters_callback(param_callback);
}
Expand All @@ -264,22 +246,24 @@ TeleopTwistJoy::~TeleopTwistJoy()
delete pimpl_;
}

double getVal(const sensor_msgs::msg::Joy::SharedPtr joy_msg, const std::map<std::string, int64_t>& axis_map,
const std::map<std::string, double>& scale_map, const std::string& fieldname)
double getVal(
const sensor_msgs::msg::Joy::SharedPtr joy_msg, const std::map<std::string, int64_t> & axis_map,
const std::map<std::string, double> & scale_map, const std::string & fieldname)
{
if (axis_map.find(fieldname) == axis_map.end() ||
axis_map.at(fieldname) == -1L ||
scale_map.find(fieldname) == scale_map.end() ||
static_cast<int>(joy_msg->axes.size()) <= axis_map.at(fieldname))
axis_map.at(fieldname) == -1L ||
scale_map.find(fieldname) == scale_map.end() ||
static_cast<int>(joy_msg->axes.size()) <= axis_map.at(fieldname))
{
return 0.0;
}

return joy_msg->axes[axis_map.at(fieldname)] * scale_map.at(fieldname);
}

void TeleopTwistJoy::Impl::sendCmdVelMsg(const sensor_msgs::msg::Joy::SharedPtr joy_msg,
const std::string& which_map)
void TeleopTwistJoy::Impl::sendCmdVelMsg(
const sensor_msgs::msg::Joy::SharedPtr joy_msg,
const std::string & which_map)
{
// Initializes with zeros by default.
auto cmd_vel_msg = std::make_unique<geometry_msgs::msg::Twist>();
Expand All @@ -298,23 +282,19 @@ void TeleopTwistJoy::Impl::sendCmdVelMsg(const sensor_msgs::msg::Joy::SharedPtr
void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::msg::Joy::SharedPtr joy_msg)
{
if (enable_turbo_button >= 0 &&
static_cast<int>(joy_msg->buttons.size()) > enable_turbo_button &&
joy_msg->buttons[enable_turbo_button])
static_cast<int>(joy_msg->buttons.size()) > enable_turbo_button &&
joy_msg->buttons[enable_turbo_button])
{
sendCmdVelMsg(joy_msg, "turbo");
}
else if (!require_enable_button ||
(static_cast<int>(joy_msg->buttons.size()) > enable_button &&
joy_msg->buttons[enable_button]))
} else if (!require_enable_button || // NOLINT
(static_cast<int>(joy_msg->buttons.size()) > enable_button &&
joy_msg->buttons[enable_button]))
{
sendCmdVelMsg(joy_msg, "normal");
}
else
{
} else {
// When enable button is released, immediately send a single no-motion command
// in order to stop the robot.
if (!sent_disable_msg)
{
if (!sent_disable_msg) {
// Initializes with zeros by default.
auto cmd_vel_msg = std::make_unique<geometry_msgs::msg::Twist>();
cmd_vel_pub->publish(std::move(cmd_vel_msg));
Expand Down

0 comments on commit 1ca5533

Please sign in to comment.