Skip to content

Commit

Permalink
Merge branch 'master' into jtc/cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Jan 4, 2024
2 parents 6f67f65 + 2b52f0b commit 922255b
Show file tree
Hide file tree
Showing 29 changed files with 165 additions and 53 deletions.
3 changes: 2 additions & 1 deletion ackermann_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(ackermann_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

# find dependencies
Expand Down
3 changes: 2 additions & 1 deletion admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(admittance_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion bicycle_steering_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(bicycle_steering_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

# find dependencies
Expand Down
2 changes: 1 addition & 1 deletion diff_drive_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(diff_drive_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wconversion)
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion effort_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(effort_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion force_torque_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(force_torque_sensor_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion forward_command_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(forward_command_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion gripper_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ if(APPLE OR WIN32)
endif()

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wconversion)
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion imu_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(imu_sensor_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
3 changes: 2 additions & 1 deletion joint_state_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(joint_state_broadcaster LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion joint_trajectory_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(joint_trajectory_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wconversion)
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
1 change: 1 addition & 0 deletions joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,7 @@ Further information

Trajectory Representation <trajectory.rst>
joint_trajectory_controller Parameters <parameters.rst>
rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst>


.. rubric:: Footnote
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,9 @@
#define JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_

#include <chrono>
#include <functional> // for std::reference_wrapper
#include <memory>
#include <mutex>
#include <string>
#include <utility>
#include <vector>

#include "control_msgs/action/follow_joint_trajectory.hpp"
Expand All @@ -30,15 +29,15 @@
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/interpolation_methods.hpp"
#include "joint_trajectory_controller/tolerances.hpp"
#include "joint_trajectory_controller/trajectory.hpp"
#include "joint_trajectory_controller/visibility_control.h"
#include "rclcpp/duration.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/timer.hpp"
#include "rclcpp_action/server.hpp"
#include "rclcpp_action/types.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_server_goal_handle.h"
Expand All @@ -50,19 +49,8 @@

using namespace std::chrono_literals; // NOLINT

namespace rclcpp_action
{
template <typename ActionT>
class ServerGoalHandle;
} // namespace rclcpp_action
namespace rclcpp_lifecycle
{
class State;
} // namespace rclcpp_lifecycle

namespace joint_trajectory_controller
{
class Trajectory;

class JointTrajectoryController : public controller_interface::ControllerInterface
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,6 @@
#ifndef JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_
#define JOINT_TRAJECTORY_CONTROLLER__TOLERANCES_HPP_

#include <cassert>
#include <cmath>
#include <string>
#include <vector>

#include "control_msgs/action/follow_joint_trajectory.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,10 @@

#include "joint_trajectory_controller/joint_trajectory_controller.hpp"

#include <stddef.h>
#include <chrono>
#include <functional>
#include <memory>
#include <ostream>
#include <ratio>

#include <string>
#include <vector>

Expand All @@ -33,15 +31,11 @@
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/event_handler.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_action/create_server.hpp"
#include "rclcpp_action/server_goal_handle.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "std_msgs/msg/header.hpp"

namespace joint_trajectory_controller
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#include <stddef.h>

#include <array>
#include <chrono>
#include <cmath>
#include <future>
Expand All @@ -30,7 +29,6 @@
#include "builtin_interfaces/msg/time.hpp"
#include "controller_interface/controller_interface.hpp"
#include "hardware_interface/resource_manager.hpp"
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/duration.hpp"
Expand All @@ -44,9 +42,6 @@
#include "rclcpp/subscription.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "std_msgs/msg/header.hpp"
#include "trajectory_msgs/msg/joint_trajectory.hpp"
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "joint_trajectory_controller/trajectory.hpp"

namespace
{
Expand Down
2 changes: 1 addition & 1 deletion pid_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.16)
project(pid_controller LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra)
add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
4 changes: 2 additions & 2 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,10 +171,10 @@ controller_interface::CallbackReturn PidController::on_configure(
if (params_.use_external_measured_states)
{
auto measured_state_callback =
[&](const std::shared_ptr<ControllerMeasuredStateMsg> msg) -> void
[&](const std::shared_ptr<ControllerMeasuredStateMsg> state_msg) -> void
{
// TODO(destogl): Sort the input values based on joint and interface names
measured_state_.writeFromNonRT(msg);
measured_state_.writeFromNonRT(state_msg);
};
measured_state_subscriber_ = get_node()->create_subscription<ControllerMeasuredStateMsg>(
"~/measured_state", subscribers_qos, measured_state_callback);
Expand Down
3 changes: 2 additions & 1 deletion position_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(position_controllers LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
2 changes: 1 addition & 1 deletion range_sensor_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ if(NOT CMAKE_CXX_STANDARD)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow -Werror=format)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
12 changes: 12 additions & 0 deletions rqt_joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/rqt_joint_trajectory_controller/doc/userdoc.rst

.. _rqt_joint_trajectory_controller_userdoc:

rqt_joint_trajectory_controller
===============================

rqt_joint_trajectory_controller is a GUI plugin for rqt that allows to command a joint_trajectory_controller.

.. image:: rqt_joint_trajectory_controller.png
:width: 400
:alt: rqt_joint_trajectory_controller
6 changes: 5 additions & 1 deletion steering_controllers_library/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@ cmake_minimum_required(VERSION 3.16)
project(steering_controllers_library LANGUAGES CXX)

if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic -Wconversion)
add_compile_options(-Wall -Wextra -Wpedantic -Werror=conversion -Werror=unused-but-set-variable
-Werror=return-type -Werror=shadow -Werror=format)
endif()

# find dependencies
Expand Down Expand Up @@ -67,6 +68,9 @@ if(BUILD_TESTING)
controller_interface
hardware_interface
)
ament_add_gmock(test_steering_odometry test/test_steering_odometry.cpp)
target_link_libraries(test_steering_odometry steering_controllers_library)

endif()

install(
Expand Down
4 changes: 2 additions & 2 deletions steering_controllers_library/src/steering_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,8 +270,8 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
double denominator_first_member = 2 * wheelbase_ * std::cos(alpha);
double denominator_second_member = wheel_track_ * std::sin(alpha);

double alpha_r = std::atan2(numerator, denominator_first_member - denominator_second_member);
double alpha_l = std::atan2(numerator, denominator_first_member + denominator_second_member);
double alpha_r = std::atan2(numerator, denominator_first_member + denominator_second_member);
double alpha_l = std::atan2(numerator, denominator_first_member - denominator_second_member);
steering_commands = {alpha_r, alpha_l};
}
return std::make_tuple(traction_commands, steering_commands);
Expand Down
Loading

0 comments on commit 922255b

Please sign in to comment.