Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
99 commits
Select commit Hold shift + click to select a range
79d5ea7
Add shell of the controller with a test
destogl Apr 21, 2021
cf6f919
Outline the admittance control pipeline
Apr 28, 2021
f3497e3
Hook up with MoveIt
Apr 28, 2021
0fc5ed7
Link against Eigen
Apr 28, 2021
968e5db
Do the pseudoinverse calculation
Apr 28, 2021
690562a
Set up transform buffer stuff
Apr 28, 2021
6ea8b76
Transform the incoming wrench
Apr 28, 2021
9511ea0
Correct the wrench transformation
Apr 28, 2021
b766b29
Minor renaming to be technically correct
Apr 28, 2021
8691453
Testable version of Admittance Controller. IK not yet enables, so the…
destogl May 6, 2021
ea9d49e
Try to integrate IK
destogl May 6, 2021
aa42923
Finish the method for forward kinematics (#4)
AndyZe May 7, 2021
6c07934
Version that could work
destogl May 7, 2021
05a518d
Corrected subscriptions types and debugging
destogl May 7, 2021
c1d90f2
Corrected some tests and extended testing
destogl May 11, 2021
a45e395
Debugging admittance controller
destogl May 11, 2021
9688414
Wait for valid wrench data
May 12, 2021
255e5ca
[WIP] Debug current joint states
May 12, 2021
b6ef47b
Now output is working
destogl May 12, 2021
ad13200
Pseudoinverse method was buggy. Use a different one.
May 13, 2021
749a57a
Admittance controller is working
destogl May 13, 2021
e049593
Remove quaternion calculation because it does not work
destogl May 14, 2021
fae67c7
Corrected admittance rule
destogl May 14, 2021
d110623
Clean up unused vars and debug statements
May 14, 2021
40fe6a4
Added test with hardware state has offset
destogl May 15, 2021
450a24d
Move calculation of admittance rule into separate method
destogl May 15, 2021
86acf22
Extract force processing and start using desired_joint_deltas
destogl May 15, 2021
068c6e8
Use JointTrajectoryPoint as internal data structure
destogl May 15, 2021
2b593e5
Use JointTrajectoryPoint internally
destogl May 17, 2021
28d2051
Added gravity compensation
destogl May 17, 2021
20fff9b
Add output of filtered forces
destogl May 17, 2021
eff3834
Try calculating target_pose differently
May 17, 2021
50992e6
Small comment cleanup
May 17, 2021
f8e1b43
Small bug fix to eliminate spurious rotations
May 17, 2021
ad8816a
Reverse lookupTransform(). The fixes coordinate frame and rotation is…
May 17, 2021
1c70454
Small fixup
May 17, 2021
0cbc428
Remove unnecessary dependencies
destogl May 18, 2021
055e7cf
Add orientation to admittance control. Small simplifications.
May 18, 2021
dbb76a7
Remove small number noise from substraction
destogl May 18, 2021
39f5a13
Remove small number noise from substraction
destogl May 19, 2021
704063e
REnaming of variables
destogl May 19, 2021
f53c0b5
Rename force->wrench to be technically correct
May 19, 2021
5ab7640
Try to debug force input
destogl May 20, 2021
5ec8851
Add update_robot_state() function
May 21, 2021
137a4ca
Rename get_current_pose_of_endeffector_frame->get_pose_of_endeffector…
May 21, 2021
f73eb5f
Small variable renaming. Refactor get_pose_of_endeffector_in_base_fra…
May 21, 2021
7c9ef25
Hard-code to always use joint commands
May 21, 2021
9a5e42e
This works but does not "spring back"
May 21, 2021
3e7bc37
Feed different transform into IK
May 21, 2021
48b962d
Rename tf arg to IK. Delete debug statements.
May 21, 2021
f16fc35
General cleanup, variable documentation and renaming
May 21, 2021
469a9f4
More renaming of force->wrench
May 25, 2021
b897a9c
Remove endeffector_frame (redundant with control_frame)
May 25, 2021
d4f98dd
Debug calculate_desired_joint_state
May 25, 2021
ba04d2b
error = target - current
May 25, 2021
ae2001d
Correct the current pose
May 26, 2021
4dee49e
Translation seems fine!
May 26, 2021
1e72d21
Delete commented code blocks
May 26, 2021
3e8d6a3
Re-enable orientation control (#13)
AndyZe May 26, 2021
d08000f
Flip the "pose error" calculation
May 27, 2021
ac73fdc
Implement "spring back" behavior. Use inertial reference frame. (#14)
AndyZe May 27, 2021
0200ecd
Pre-allocate an identity transform
May 27, 2021
d8ffba0
Add feedforward acceleration term (#15)
AndyZe May 28, 2021
59518db
configure() admittance differently. Fixes "XBox first" bug
May 28, 2021
cb9facc
Revert endeffector frame to publish forces in endeffector frame
destogl May 30, 2021
313eabe
Enable support of NaN values on command interface
destogl May 30, 2021
2e0f7fd
Add JointDeltas output to see what is happening before XBox is enabled
destogl May 30, 2021
2611ad5
Squash "not-moving before XBox" bug
destogl May 30, 2021
404bcc9
Enable open loop control (#16)
destogl Jun 1, 2021
877b6de
Rename feedforward_pose variable to target_from_joint_deltas
destogl Jun 3, 2021
8b9607a
Correct rotation issues. Stability is reduced.
destogl Jun 5, 2021
4be5909
Implement get_link_transform(). Rename IncrementalKinematics
Jun 3, 2021
e2cb89a
Renaming of incremental_kinematics -> moveit_kinematics
Jun 3, 2021
0c09d4e
Added Andy as author and correct include style.
destogl Jun 5, 2021
520f573
Update moveit kinematics accepting current joint_state
Jun 6, 2021
b559128
Adjust formating of moveit kinematics file.
destogl Jun 6, 2021
951b85d
Rename desired to reference and interal variables with prefix admittance
destogl Jun 6, 2021
2826ad6
Seems working. Neede one more round of checks.
destogl Jun 6, 2021
1cfbf0c
Cleaning of the not used feedforward variables.
destogl Jun 6, 2021
a5a11fc
Change approach of calculating absolute desired pose.
destogl Jun 6, 2021
30cd6f3
Use logic to force stable behavior when no external forces are measured.
destogl Jun 6, 2021
d616f73
Rename the wrench variable (ik_base, not control frame)
Jun 7, 2021
ec65af4
Use simple forward diff formula. Delete unused vars. Set admittance v…
Jun 7, 2021
478a0e9
Different "pose error" calculation for open-loop mode. Prevents rotat…
Jun 7, 2021
1b7a679
Resort calculation of admittance displacement to have it in one place
destogl Jun 7, 2021
ef0cda8
Do not initialize memory in update joint-deltas method. Simplify calc…
destogl Jun 7, 2021
3a5e111
Comment gravity comp parameter parsing, for now
Jun 8, 2021
62f7671
Delete unused EPSILON variables
Jun 8, 2021
a0f275f
Add admittance controller compile options
destogl Jun 7, 2021
726c1a7
Add filter_chain_ definition
destogl Jun 7, 2021
400a374
Add filter chain to admittance controller
destogl Jun 7, 2021
dde2cb2
Enalbe filters by moving admittance_rule impl to a header file.
destogl Jun 8, 2021
6d67a1a
Remove protection logic since it is not needed anymore
destogl Jun 9, 2021
6ae99ef
Remove unused code
destogl Jun 9, 2021
ef39450
Add Admittance Controller from 79a2dfe78c73f9a99e899f4bb400424783a202…
destogl Oct 21, 2021
e1eebd9
Compilable with changed controllers' update() api -> against destogl:…
destogl Oct 21, 2021
7120817
Add debuging output to the AdmittanceController to know when SRDF is …
destogl Oct 26, 2021
d29d6c2
Update to new version of ControlParameters and add enable_paramter_up…
destogl Oct 28, 2021
ed51262
Use updated ParameterHandler from control_toolbox.
destogl Oct 31, 2021
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
134 changes: 134 additions & 0 deletions admittance_controller/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
cmake_minimum_required(VERSION 3.5)
project(admittance_controller)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(control_msgs REQUIRED)
find_package(control_toolbox REQUIRED)
find_package(controller_interface REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(filters REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(joint_limits REQUIRED)
find_package(moveit_ros_move_group REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(realtime_tools REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)

add_library(
admittance_controller
SHARED
src/admittance_controller.cpp
src/moveit_kinematics.cpp
)
target_include_directories(
admittance_controller
PRIVATE
include
)
ament_target_dependencies(
admittance_controller
control_msgs
control_toolbox
controller_interface
${Eigen_LIBRARIES}
filters
geometry_msgs
hardware_interface
joint_limits
moveit_ros_move_group
moveit_ros_planning_interface
pluginlib
rclcpp
rclcpp_lifecycle
realtime_tools
tf2
tf2_eigen
tf2_geometry_msgs
tf2_ros
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(admittance_controller PRIVATE "ADMITTANCE_CONTROLLER_BUILDING_DLL")

pluginlib_export_plugin_description_file(controller_interface admittance_controller.xml)

install(
TARGETS admittance_controller
RUNTIME DESTINATION bin
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
)

install(
DIRECTORY include/
DESTINATION include
)

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(controller_manager REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(ros2_control_test_assets REQUIRED)

ament_add_gmock(test_load_admittance_controller test/test_load_admittance_controller.cpp)
target_include_directories(test_load_admittance_controller PRIVATE include)
ament_target_dependencies(
test_load_admittance_controller
controller_manager
hardware_interface
ros2_control_test_assets
)

ament_add_gmock(test_admittance_controller test/test_admittance_controller.cpp)
target_include_directories(test_admittance_controller PRIVATE include)
target_link_libraries(test_admittance_controller admittance_controller)
ament_target_dependencies(
test_admittance_controller
control_msgs
controller_interface
hardware_interface
ros2_control_test_assets
)
endif()

ament_export_include_directories(
include
)
ament_export_libraries(
admittance_controller
)
ament_export_dependencies(
control_msgs
control_toolbox
controller_interface
filters
geometry_msgs
hardware_interface
joint_limits
pluginlib
rclcpp
rclcpp_lifecycle
realtime_tools
tf2
tf2_eigen
tf2_geometry_msgs
tf2_ros
)

ament_package()
7 changes: 7 additions & 0 deletions admittance_controller/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
admittance_controller
==========================================

Implemenation of admittance controllers for different input and output interface.

Pluginlib-Library: admittance_controller
Plugin: admittance_controller/AdmittanceController (controller_interface::ControllerInterface)
8 changes: 8 additions & 0 deletions admittance_controller/admittance_controller.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<library path="admittance_controller">
<class name="admittance_controller/AdmittanceController"
type="admittance_controller::AdmittanceController" base_class_type="controller_interface::ControllerInterface">
<description>
AdmittanceController ros2_control controller.
</description>
</class>
</library>
Original file line number Diff line number Diff line change
@@ -0,0 +1,160 @@
// Copyright (c) 2021, PickNik, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
/// \authors: Denis Stogl, Andy Zelenak

#ifndef ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
#define ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_

#include <memory>
#include <string>
#include <vector>

#include "admittance_controller/admittance_rule.hpp"
#include "admittance_controller/visibility_control.h"
#include "control_msgs/msg/admittance_controller_state.hpp"
#include "controller_interface/controller_interface.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/wrench_stamped.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_limits/joint_limiter_interface.hpp"
#include "joint_limits/joint_limits.hpp"
#include "pluginlib/class_loader.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 "semantic_components/force_torque_sensor.hpp"
// TODO(destogl): this is only temporary to work with servo. It should be either trajectory_msgs/msg/JointTrajectoryPoint or std_msgs/msg/Float64MultiArray
#include "trajectory_msgs/msg/joint_trajectory.hpp"

namespace admittance_controller
{
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class AdmittanceController : public controller_interface::ControllerInterface
{
public:
ADMITTANCE_CONTROLLER_PUBLIC
AdmittanceController();

ADMITTANCE_CONTROLLER_PUBLIC
CallbackReturn on_init() override;

ADMITTANCE_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration command_interface_configuration() const override;

ADMITTANCE_CONTROLLER_PUBLIC
controller_interface::InterfaceConfiguration state_interface_configuration() const override;

ADMITTANCE_CONTROLLER_PUBLIC
CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;

ADMITTANCE_CONTROLLER_PUBLIC
CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override;

ADMITTANCE_CONTROLLER_PUBLIC
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;

ADMITTANCE_CONTROLLER_PUBLIC
controller_interface::return_type update(
const rclcpp::Time & time, const rclcpp::Duration & period) override;

protected:
std::vector<std::string> joint_names_;
std::vector<std::string> command_interface_types_;
std::vector<std::string> state_interface_types_;
std::string ft_sensor_name_;
bool use_joint_commands_as_input_;
std::string joint_limiter_type_;

bool hardware_state_has_offset_;
trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_;

// joint limiter
using JointLimiter = joint_limits::JointLimiterInterface<joint_limits::JointLimits>;
std::shared_ptr<pluginlib::ClassLoader<JointLimiter>> joint_limiter_loader_;
std::unique_ptr<JointLimiter> joint_limiter_;

// Internal variables
std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;

// Admittance rule and dependent variables;
std::unique_ptr<admittance_controller::AdmittanceRule> admittance_;
rclcpp::Time previous_time_;

// Callback for updating dynamic parameters
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_callback_handle_;

// Command subscribers and Controller State publisher
using ControllerCommandWrenchMsg = geometry_msgs::msg::WrenchStamped;
using ControllerCommandPoseMsg = geometry_msgs::msg::PoseStamped;
using ControllerCommandJointMsg = trajectory_msgs::msg::JointTrajectory;

rclcpp::Subscription<ControllerCommandWrenchMsg>::SharedPtr
input_wrench_command_subscriber_ = nullptr;
rclcpp::Subscription<ControllerCommandPoseMsg>::SharedPtr
input_pose_command_subscriber_ = nullptr;
rclcpp::Subscription<ControllerCommandJointMsg>::SharedPtr input_joint_command_subscriber_ = nullptr;

realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerCommandWrenchMsg>>
input_wrench_command_;
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerCommandPoseMsg>>
input_pose_command_;
realtime_tools::RealtimeBuffer<std::shared_ptr<ControllerCommandJointMsg>>
input_joint_command_;

using ControllerStateMsg = control_msgs::msg::AdmittanceControllerState;
using ControllerStatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;

rclcpp::Publisher<ControllerStateMsg>::SharedPtr s_publisher_;
std::unique_ptr<ControllerStatePublisher> state_publisher_;

// Internal access to sorted interfaces

// To reduce number of variables and to make the code shorter the interfaces are ordered in types
// as the following constants
const std::vector<std::string> allowed_interface_types_ = {
hardware_interface::HW_IF_POSITION,
hardware_interface::HW_IF_VELOCITY,
};

// The interfaces are defined as the types in 'allowed_interface_types_' member.
// For convenience, for each type the interfaces are ordered so that i-th position
// matches i-th index in joint_names_
template<typename T>
using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;

InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;

bool has_velocity_state_interface_ = false;
bool has_position_command_interface_ = false;
bool has_velocity_command_interface_ = false;

void read_state_from_hardware(trajectory_msgs::msg::JointTrajectoryPoint & state);

/// Use values on command interfaces as states when robot should be controller in open-loop.
/**
* If velocities and positions are both available from the joint command interface, set
* output_state equal to them.
* If velocities or positions are unknown, output_state is unchanged and the function returns false.
*/
bool read_state_from_command_interfaces(trajectory_msgs::msg::JointTrajectoryPoint & state);
};

} // namespace admittance_controller

#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@

// Header!!
std::string ik_tip_frame_;

// Frame which position should be controlled
std::string endeffector_frame_;

tf2::Transform ik_tip_to_control_frame_tf_;
tf2::Transform control_frame_to_ik_tip_tf_;

// CPP!!
controller_interface::return_type AdmittanceRule::reset()
{
// Initialize ik_tip and tool_frame transformations - those are fixed transformations
tf2::Stamped<tf2::Transform> tf2_transform;
try {
auto transform = tf_buffer_->lookupTransform(ik_tip_frame_, control_frame_, tf2::TimePointZero);
tf2::fromMsg(transform, tf2_transform);
ik_tip_to_control_frame_tf_ = tf2_transform;
control_frame_to_ik_tip_tf_ = tf2_transform.inverse();
} catch (const tf2::TransformException & e) {
RCLCPP_ERROR_SKIPFIRST_THROTTLE(
rclcpp::get_logger("AdmittanceRule"), *clock_, 5000, "%s", e.what());
return controller_interface::return_type::ERROR;
}
}


controller_interface::return_type AdmittanceRule::get_controller_state(
control_msgs::msg::AdmittanceControllerState & state_message)
{
// FIXME(destogl): Something is wrong with this transformation - check frames...
try {
auto transform = tf_buffer_->lookupTransform(endeffector_frame_, control_frame_, tf2::TimePointZero);
tf2::doTransform(measured_wrench_ik_base_frame_, measured_wrench_endeffector_frame_, transform);
} catch (const tf2::TransformException & e) {
RCLCPP_ERROR_SKIPFIRST_THROTTLE(
rclcpp::get_logger("AdmittanceRule"), *clock_, 5000, "%s", e.what());
}
state_message.measured_wrench_endeffector_frame = measured_wrench_endeffector_frame_;
}
Loading