Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -37,17 +37,17 @@
#pragma once
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <realtime_tools/realtime_buffer.h>
#include <array>
#include <memory>

#include <controller_interface/controller_interface.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <realtime_tools/realtime_buffer.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <ur_msgs/srv/set_force_mode.hpp>

#include "force_mode_controller_parameters.hpp"
#include "ur_controllers/force_mode_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
#include <rclcpp/duration.hpp>
#include "std_msgs/msg/bool.hpp"

#include "freedrive_mode_controller_parameters.hpp"
#include "ur_controllers/freedrive_mode_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
2 changes: 1 addition & 1 deletion ur_controllers/include/ur_controllers/gpio_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "std_msgs/msg/bool.hpp"
#include "gpio_controller_parameters.hpp"
#include "ur_controllers/gpio_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,6 @@

#include <stdint.h>

#include <realtime_tools/realtime_buffer.h>
#include <realtime_tools/realtime_server_goal_handle.h>

#include <functional>
#include <limits>
#include <memory>
Expand All @@ -54,6 +51,8 @@
#include <vector>

#include <controller_interface/controller_interface.hpp>
#include <realtime_tools/realtime_buffer.hpp>
#include <realtime_tools/realtime_server_goal_handle.hpp>
#include <rclcpp_action/server.hpp>
#include <rclcpp_action/create_server.hpp>
#include <rclcpp/rclcpp.hpp>
Expand All @@ -65,7 +64,7 @@
#include <trajectory_msgs/msg/joint_trajectory.hpp>
#include <control_msgs/action/follow_joint_trajectory.hpp>

#include "passthrough_trajectory_controller_parameters.hpp"
#include "ur_controllers/passthrough_trajectory_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "scaled_joint_trajectory_controller_parameters.hpp"
#include "ur_controllers/scaled_joint_trajectory_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "std_msgs/msg/float64.hpp"
#include "speed_scaling_state_broadcaster_parameters.hpp"
#include "ur_controllers/speed_scaling_state_broadcaster_parameters.hpp"

namespace ur_controllers
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,14 +43,14 @@

// TODO(fmauch): Currently, the realtime_box_best_effort doesn't include this
#include <functional>
#include <realtime_tools/realtime_box_best_effort.h> // NOLINT

#include <memory>

#include <controller_interface/controller_interface.hpp>
#include <realtime_tools/realtime_box_best_effort.hpp>

#include "ur_msgs/srv/get_robot_software_version.hpp"
#include "ur_configuration_controller_parameters.hpp"
#include "ur_controllers/ur_configuration_controller_parameters.hpp"

namespace ur_controllers
{
Expand Down
1 change: 1 addition & 0 deletions ur_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

<depend>angles</depend>
<depend>controller_interface</depend>
<depend>generate_parameter_library</depend>
<depend>geometry_msgs</depend>
<depend>hardware_interface</depend>
<depend>joint_trajectory_controller</depend>
Expand Down
2 changes: 1 addition & 1 deletion ur_controllers/src/gpio_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -407,7 +407,7 @@ bool GPIOController::setAnalogOutput(ur_msgs::srv::SetAnalogOutput::Request::Sha
return false;
}

if (req->data.pin < 0 || req->data.pin > 1) {
if (!(req->data.pin == 0 || req->data.pin == 1)) {
RCLCPP_ERROR(get_node()->get_logger(), "Invalid pin selected. Only pins 0 and 1 are allowed.");
resp->success = false;
return false;
Expand Down
2 changes: 1 addition & 1 deletion ur_controllers/src/ur_configuration_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
//----------------------------------------------------------------------

#include <ur_controllers/ur_configuration_controller.hpp>
#include <realtime_tools/realtime_box.h>
#include <realtime_tools/realtime_box.hpp>
namespace ur_controllers
{

Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/src/ur_ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
// ROS includes
#include "controller_manager/controller_manager.hpp"
#include "rclcpp/rclcpp.hpp"
#include "realtime_tools/thread_priority.hpp"
#include "realtime_tools/realtime_helpers.hpp"

// code is inspired by
// https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/ros2_control_node.cpp
Expand Down