Skip to content

Commit

Permalink
Merge branch 'master' into mv/speed_limiter
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 6, 2024
2 parents 2d5e6f3 + dc60f6f commit 58b114c
Show file tree
Hide file tree
Showing 20 changed files with 45 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#include "rclcpp/duration.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "semantic_components/force_torque_sensor.hpp"

namespace admittance_controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
#include "nav_msgs/msg/odometry.hpp"
#include "odometry.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_box.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_box.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "tf2_msgs/msg/tf_message.hpp"

// auto-generated by generate_parameter_library
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include "force_torque_sensor_broadcaster_parameters.hpp"
#include "geometry_msgs/msg/wrench_stamped.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "semantic_components/force_torque_sensor.hpp"

namespace force_torque_sensor_broadcaster
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "forward_command_controller/visibility_control.h"
#include "rclcpp/subscription.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "std_msgs/msg/float64_multi_array.hpp"

namespace forward_command_controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@
#include "gpio_controllers/visibility_control.h"
#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_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"

namespace gpio_controllers
{
Expand Down
16 changes: 14 additions & 2 deletions gpio_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,21 @@
<name>gpio_controllers</name>
<version>4.15.0</version>
<description>Controllers to interact with gpios.</description>
<maintainer email="[email protected]">Maciej Bednarczyk</maintainer>
<maintainer email="[email protected]">Wiktor Bajor</maintainer>

<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
<maintainer email="[email protected]">Christoph Froehlich</maintainer>
<maintainer email="[email protected]">Sai Kishor Kothakota</maintainer>

<license>Apache License 2.0</license>

<url type="website">https://control.ros.org</url>
<url type="bugtracker">https://github.com/ros-controls/ros2_controllers/issues</url>
<url type="repository">https://github.com/ros-controls/ros2_controllers/</url>

<author email="[email protected]">Maciej Bednarczyk</author>
<author email="[email protected]">Wiktor Bajor</author>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>controller_interface</depend>
Expand All @@ -22,6 +33,7 @@

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>controller_manager</test_depend>
<test_depend>hardware_interface_testing</test_depend>
<test_depend>ros2_control_test_assets</test_depend>

<export>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include "gripper_controllers/visibility_control.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_server_goal_handle.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_server_goal_handle.hpp"

// Project
#include "gripper_controllers/hardware_interface_adapter.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
// auto-generated by generate_parameter_library
#include "imu_sensor_broadcaster_parameters.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "semantic_components/imu_sensor.hpp"
#include "sensor_msgs/msg/imu.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "joint_state_broadcaster/visibility_control.h"
// auto-generated by generate_parameter_library
#include "joint_state_broadcaster_parameters.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "urdf/model.h"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@
#include "rclcpp/timer.hpp"
#include "rclcpp_action/server.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"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "realtime_tools/realtime_server_goal_handle.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 @@ -29,8 +29,8 @@
#include "mecanum_drive_controller_parameters.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_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "std_srvs/srv/set_bool.hpp"

#include "control_msgs/msg/mecanum_drive_controller_state.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define MECANUM_DRIVE_CONTROLLER__ODOMETRY_HPP_

#include "geometry_msgs/msg/twist.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"

#define PLANAR_POINT_DIM 3

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "parallel_gripper_controller/visibility_control.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_server_goal_handle.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_server_goal_handle.hpp"

// Project
#include "parallel_gripper_action_controller_parameters.hpp"
Expand Down
4 changes: 2 additions & 2 deletions pid_controller/include/pid_controller/pid_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@
#include "pid_controller/visibility_control.h"
#include "pid_controller_parameters.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "std_srvs/srv/set_bool.hpp"

namespace pid_controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "pose_broadcaster_parameters.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "semantic_components/pose_sensor.hpp"
#include "tf2_msgs/msg/tf_message.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#include "range_sensor_broadcaster/visibility_control.h"
#include "range_sensor_broadcaster_parameters.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_publisher.hpp"
#include "semantic_components/range_sensor.hpp"
#include "sensor_msgs/msg/range.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,14 +70,10 @@ def main(args=None):

try:
rclpy.spin(publisher_forward_position)
except KeyboardInterrupt:
except (KeyboardInterrupt, rclpy.executors.ExternalShutdownException):
print("Keyboard interrupt received. Shutting down node.")
except Exception as e:
print(f"Unhandled exception: {e}")
finally:
if rclpy.ok():
publisher_forward_position.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,14 +186,10 @@ def main(args=None):

try:
rclpy.spin(publisher_joint_trajectory)
except KeyboardInterrupt:
except (KeyboardInterrupt, rclpy.executors.ExternalShutdownException):
print("Keyboard interrupt received. Shutting down node.")
except Exception as e:
print(f"Unhandled exception: {e}")
finally:
if rclpy.ok():
publisher_joint_trajectory.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#include "controller_interface/chainable_controller_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_buffer.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "steering_controllers_library/steering_odometry.hpp"
#include "steering_controllers_library/visibility_control.h"
#include "steering_controllers_library_parameters.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "realtime_tools/realtime_box.h"
#include "realtime_tools/realtime_publisher.h"
#include "realtime_tools/realtime_box.hpp"
#include "realtime_tools/realtime_publisher.hpp"
#include "std_srvs/srv/empty.hpp"
#include "tf2_msgs/msg/tf_message.hpp"
#include "tricycle_controller/odometry.hpp"
Expand Down

0 comments on commit 58b114c

Please sign in to comment.