Skip to content

Commit 299b983

Browse files
committed
Add force torque controller.
1 parent f8f5044 commit 299b983

File tree

5 files changed

+293
-28
lines changed

5 files changed

+293
-28
lines changed

ur_controllers/CMakeLists.txt

Lines changed: 36 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,35 +1,52 @@
11
cmake_minimum_required(VERSION 3.5)
22
project(ur_controllers)
33

4-
add_compile_options(-std=c++11)
4+
# Default to C++14
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 14)
7+
endif()
8+
9+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10+
add_compile_options(-Wall -Wextra)
11+
endif()
512

613
find_package(ament_cmake REQUIRED)
714
find_package(controller_interface REQUIRED)
8-
find_package(hardware_interface REQUIRED)
915
find_package(joint_trajectory_controller REQUIRED)
1016
find_package(pluginlib REQUIRED)
11-
find_package(realtime_tools REQUIRED)
1217
find_package(std_msgs REQUIRED)
18+
find_package(geometry_msgs REQUIRED)
19+
find_package(rclcpp_lifecycle REQUIRED)
20+
find_package(rcutils REQUIRED)
1321

1422
set(THIS_PACKAGE_INCLUDE_DEPENDS
15-
controller_interface
16-
hardware_interface
17-
joint_trajectory_controller
18-
pluginlib
19-
realtime_tools
20-
std_msgs
23+
controller_interface
24+
joint_trajectory_controller
25+
pluginlib
26+
std_msgs
27+
geometry_msgs
28+
rclcpp_lifecycle
29+
rcutils
2130
)
2231

2332
include_directories(include)
2433

2534
add_library(${PROJECT_NAME} SHARED
2635
src/scaled_joint_trajectory_controller.cpp
2736
src/speed_scaling_state_controller.cpp
28-
)
37+
src/force_torque_sensor_controller.cpp
38+
include/ur_controllers/force_torque_sensor_controller.h src/force_torque_sensor_controller.cpp)
39+
40+
target_include_directories(${PROJECT_NAME} PRIVATE include)
41+
2942
ament_target_dependencies(${PROJECT_NAME}
3043
${THIS_PACKAGE_INCLUDE_DEPENDS}
3144
)
3245

46+
# prevent pluginlib from using boost
47+
target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
48+
pluginlib_export_plugin_description_file(controller_interface controller_plugins.xml)
49+
3350
install(TARGETS ${PROJECT_NAME}
3451
ARCHIVE DESTINATION lib
3552
LIBRARY DESTINATION lib
@@ -46,4 +63,13 @@ install(FILES controller_plugins.xml
4663

4764
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
4865

66+
ament_export_include_directories(
67+
include
68+
)
69+
70+
ament_export_libraries(
71+
${PROJECT_NAME}
72+
)
73+
74+
4975
ament_package()
Lines changed: 22 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,24 @@
1-
<library path="lib/libur_controllers">
2-
<class name="ur_controllers/SpeedScalingStateController" type="ur_controllers::SpeedScalingStateController" base_class_type="controller_interface::ControllerBase">
3-
<description>
4-
This controller publishes the readings of all available speed scaling factors.
5-
</description>
6-
</class>
7-
<class name="position_controllers/ScaledJointTrajectoryController" type="position_controllers::ScaledJointTrajectoryController" base_class_type="controller_interface::ControllerBase">
8-
<description>
9-
Scaled velocity-based joint trajectory controller
10-
</description>
11-
</class>
12-
<class name="velocity_controllers/ScaledJointTrajectoryController" type="velocity_controllers::ScaledJointTrajectoryController" base_class_type="controller_interface::ControllerBase">
13-
<description>
14-
Scaled velocity-based joint trajectory controller
15-
</description>
1+
<library path="ur_controllers">
2+
<class name="ur_controllers/ForceTorqueStateController" type="ur_controllers::ForceTorqueStateController" base_class_type="controller_interface::ControllerInterface">
3+
<description>
4+
The force torque state controller publishes the current force and torques
5+
</description>
166
</class>
177
</library>
8+
<!--<library path="lib/libur_controllers">-->
9+
<!--<class name="ur_controllers/SpeedScalingStateController" type="ur_controllers::SpeedScalingStateController" base_class_type="controller_interface::ControllerBase">-->
10+
<!--<description>-->
11+
<!--This controller publishes the readings of all available speed scaling factors.-->
12+
<!--</description>-->
13+
<!--</class>-->
14+
<!--<class name="position_controllers/ScaledJointTrajectoryController" type="position_controllers::ScaledJointTrajectoryController" base_class_type="controller_interface::ControllerBase">-->
15+
<!--<description>-->
16+
<!--Scaled velocity-based joint trajectory controller-->
17+
<!--</description>-->
18+
<!--</class>-->
19+
<!--<class name="velocity_controllers/ScaledJointTrajectoryController" type="velocity_controllers::ScaledJointTrajectoryController" base_class_type="controller_interface::ControllerBase">-->
20+
<!--<description>-->
21+
<!--Scaled velocity-based joint trajectory controller-->
22+
<!--</description>-->
23+
<!--</class>-->
24+
<!--</library>-->
Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
//
2+
// Created by livanov93 on 12/12/20.
3+
//
4+
5+
#ifndef UR_CONTROLLERS_FORCE_TORQUE_SENSOR_CONTROLLER_H
6+
#define UR_CONTROLLERS_FORCE_TORQUE_SENSOR_CONTROLLER_H
7+
8+
#include <memory>
9+
#include <string>
10+
#include <unordered_map>
11+
#include <vector>
12+
13+
#include <controller_interface/controller_interface.hpp>
14+
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
15+
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
16+
17+
#include <geometry_msgs/msg/wrench_stamped.hpp>
18+
19+
namespace ur_controllers
20+
{
21+
class ForceTorqueStateController : public controller_interface::ControllerInterface
22+
{
23+
public:
24+
ForceTorqueStateController();
25+
26+
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
27+
28+
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
29+
30+
controller_interface::return_type update() override;
31+
32+
CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
33+
34+
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
35+
36+
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
37+
38+
protected:
39+
bool init_sensor_data();
40+
void init_sensor_state_msg();
41+
42+
// we store the name of values per axis - compatible interfaces
43+
std::vector<std::string> axis_val_names_;
44+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::WrenchStamped>> wrench_state_publisher_;
45+
geometry_msgs::msg::WrenchStamped wrench_state_msg_;
46+
};
47+
} // namespace ur_controllers
48+
49+
#endif // UR_CONTROLLERS_FORCE_TORQUE_SENSOR_CONTROLLER_H

ur_controllers/package.xml

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,12 +11,20 @@
1111

1212
<buildtool_depend>ament_cmake</buildtool_depend>
1313

14+
<build_depend>pluginlib</build_depend>
15+
<build_depend>rcutils</build_depend>
16+
17+
<exec_depend>pluginlib</exec_depend>
18+
<exec_depend>rcutils</exec_depend>
19+
1420
<depend>controller_interface</depend>
15-
<depend>hardware_interface</depend>
21+
<depend>rclcpp_lifecycle</depend>
22+
<depend>geometry_msgs</depend>
1623
<depend>joint_trajectory_controller</depend>
17-
<depend>pluginlib</depend>
18-
<depend>realtime_tools</depend>
1924
<depend>std_msgs</depend>
25+
<depend>std_srvs</depend>
26+
<depend>ur_client_library</depend>
27+
<depend>ur_dashboard_msgs</depend>
2028

2129
<export>
2230
<build_type>ament_cmake</build_type>
Lines changed: 175 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,175 @@
1+
//
2+
// Created by livanov93 on 12/12/20.
3+
//
4+
5+
#include "ur_controllers/force_torque_sensor_controller.h"
6+
7+
namespace ur_controllers
8+
{
9+
ForceTorqueStateController::ForceTorqueStateController() : controller_interface::ControllerInterface()
10+
{
11+
}
12+
13+
controller_interface::InterfaceConfiguration ForceTorqueStateController::command_interface_configuration() const
14+
{
15+
controller_interface::InterfaceConfiguration config;
16+
config.type = controller_interface::interface_configuration_type::NONE;
17+
return config;
18+
}
19+
20+
controller_interface::InterfaceConfiguration ForceTorqueStateController::state_interface_configuration() const
21+
{
22+
controller_interface::InterfaceConfiguration config;
23+
config.type = controller_interface::interface_configuration_type::ALL;
24+
return config;
25+
}
26+
27+
controller_interface::return_type ur_controllers::ForceTorqueStateController::update()
28+
{
29+
geometry_msgs::msg::Vector3 fVec;
30+
geometry_msgs::msg::Vector3 tVec;
31+
32+
// TODO remove these hardcoded names and create better string filtering within state_interfaces_
33+
for (const auto& state_interface : state_interfaces_)
34+
{
35+
if (state_interface.get_name() != "tcp_fts_sensor")
36+
continue;
37+
38+
if (state_interface.get_interface_name() == "fx")
39+
{
40+
fVec.set__x(state_interface.get_value());
41+
continue;
42+
}
43+
44+
if (state_interface.get_interface_name() == "fy")
45+
{
46+
fVec.set__y(state_interface.get_value());
47+
continue;
48+
}
49+
50+
if (state_interface.get_interface_name() == "fz")
51+
{
52+
fVec.set__z(state_interface.get_value());
53+
continue;
54+
}
55+
56+
if (state_interface.get_interface_name() == "tx")
57+
{
58+
tVec.set__x(state_interface.get_value());
59+
continue;
60+
}
61+
62+
if (state_interface.get_interface_name() == "ty")
63+
{
64+
tVec.set__y(state_interface.get_value());
65+
continue;
66+
}
67+
68+
if (state_interface.get_interface_name() == "tz")
69+
{
70+
tVec.set__z(state_interface.get_value());
71+
continue;
72+
}
73+
}
74+
75+
if (!wrench_state_publisher_->is_activated())
76+
{
77+
RCUTILS_LOG_WARN_ONCE_NAMED("publisher", "wrench state publisher is not activated");
78+
return controller_interface::return_type::ERROR;
79+
}
80+
81+
// TODO set frame_id as parameter --> it includes tf listener within controller
82+
wrench_state_msg_.header.stamp = lifecycle_node_->get_clock()->now();
83+
wrench_state_msg_.header.frame_id = "tool0";
84+
85+
// update wrench state message
86+
wrench_state_msg_.wrench.set__force(fVec);
87+
wrench_state_msg_.wrench.set__torque(tVec);
88+
89+
// publish
90+
wrench_state_publisher_->publish(wrench_state_msg_);
91+
92+
return controller_interface::return_type::SUCCESS;
93+
}
94+
95+
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
96+
ForceTorqueStateController::on_configure(const rclcpp_lifecycle::State& /*previous_state*/)
97+
{
98+
try
99+
{
100+
// TODO make topic name a parameter
101+
wrench_state_publisher_ =
102+
lifecycle_node_->create_publisher<geometry_msgs::msg::WrenchStamped>("ft_data", rclcpp::SystemDefaultsQoS());
103+
}
104+
catch (...)
105+
{
106+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
107+
}
108+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
109+
}
110+
111+
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
112+
ForceTorqueStateController::on_activate(const rclcpp_lifecycle::State& /*previous_state*/)
113+
{
114+
if (!init_sensor_data())
115+
{
116+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
117+
}
118+
119+
init_sensor_state_msg();
120+
121+
wrench_state_publisher_->on_activate();
122+
123+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
124+
}
125+
126+
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
127+
ForceTorqueStateController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
128+
{
129+
wrench_state_publisher_->on_deactivate();
130+
131+
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
132+
}
133+
134+
template <typename T>
135+
bool has_any_key(const std::unordered_map<std::string, T>& map, const std::vector<std::string>& keys)
136+
{
137+
bool found_key = false;
138+
for (const auto& key_item : map)
139+
{
140+
const auto& key = key_item.first;
141+
if (std::find(keys.cbegin(), keys.cend(), key) != keys.cend())
142+
{
143+
found_key = true;
144+
break;
145+
}
146+
}
147+
return found_key;
148+
}
149+
150+
bool ForceTorqueStateController::init_sensor_data()
151+
{
152+
bool has_fts_sensor = false;
153+
// loop in reverse order, this maintains the order of values at retrieval time
154+
for (auto si = state_interfaces_.crbegin(); si != state_interfaces_.crend(); si++)
155+
{
156+
// TODO remove hardcoded naming
157+
if (si->get_name() == "tcp_fts_sensor")
158+
{
159+
has_fts_sensor = true;
160+
axis_val_names_.push_back(si->get_interface_name());
161+
}
162+
}
163+
return has_fts_sensor;
164+
}
165+
166+
void ForceTorqueStateController::init_sensor_state_msg()
167+
{
168+
// default initialization for wrenchstamped state message
169+
}
170+
171+
} // namespace ur_controllers
172+
173+
#include "pluginlib/class_list_macros.hpp"
174+
175+
PLUGINLIB_EXPORT_CLASS(ur_controllers::ForceTorqueStateController, controller_interface::ControllerInterface)

0 commit comments

Comments
 (0)