diff --git a/cartesian_controller_base/CMakeLists.txt b/cartesian_controller_base/CMakeLists.txt index bec8300d..817281e9 100644 --- a/cartesian_controller_base/CMakeLists.txt +++ b/cartesian_controller_base/CMakeLists.txt @@ -32,6 +32,7 @@ find_package(kdl_parser REQUIRED) find_package(trajectory_msgs REQUIRED) find_package(pluginlib REQUIRED) find_package(urdf REQUIRED) +find_package(realtime_tools REQUIRED) # Convenience variable for dependencies @@ -42,6 +43,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS pluginlib urdf Eigen3 + realtime_tools ) ament_export_dependencies( diff --git a/cartesian_controller_base/include/cartesian_controller_base/cartesian_controller_base.h b/cartesian_controller_base/include/cartesian_controller_base/cartesian_controller_base.h index 458e88d8..32ddb3c5 100644 --- a/cartesian_controller_base/include/cartesian_controller_base/cartesian_controller_base.h +++ b/cartesian_controller_base/include/cartesian_controller_base/cartesian_controller_base.h @@ -47,6 +47,8 @@ #include #include #include +#include +#include #include #include #include @@ -54,6 +56,7 @@ #include #include #include +#include #include #include #include @@ -185,6 +188,23 @@ class CartesianControllerBase : public controller_interface::ControllerInterface m_joint_state_pos_handles; private: + + /** + * @brief Publish the controller's end-effector pose and twist + * + * The data are w.r.t. the specified robot base link. + * If this function is called after `computeJointControlCmds()` has + * been called, then the controller's internal state represents the state + * right after the error computation, and corresponds to the new target + * state that will be send to the actuators in this control cycle. + */ + void publishStateFeedback(); + + realtime_tools::RealtimePublisherSharedPtr + m_feedback_pose_publisher; + realtime_tools::RealtimePublisherSharedPtr + m_feedback_twist_publisher; + std::vector m_cmd_interface_types; std::vector> m_joint_cmd_pos_handles; std::vector> m_joint_cmd_vel_handles; diff --git a/cartesian_controller_base/package.xml b/cartesian_controller_base/package.xml index e08510c1..ba429c89 100644 --- a/cartesian_controller_base/package.xml +++ b/cartesian_controller_base/package.xml @@ -16,6 +16,7 @@ kdl_parser trajectory_msgs pluginlib + realtime_tools ament_cmake diff --git a/cartesian_controller_base/src/cartesian_controller_base.cpp b/cartesian_controller_base/src/cartesian_controller_base.cpp index 1c24fe3b..795db668 100644 --- a/cartesian_controller_base/src/cartesian_controller_base.cpp +++ b/cartesian_controller_base/src/cartesian_controller_base.cpp @@ -39,6 +39,8 @@ #include "controller_interface/controller_interface.hpp" #include "controller_interface/helpers.hpp" +#include "geometry_msgs/msg/detail/pose_stamped__struct.hpp" +#include "geometry_msgs/msg/detail/twist_stamped__struct.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include @@ -96,6 +98,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Cartes auto_declare>("command_interfaces", std::vector()); auto_declare("solver.error_scale", 1.0); auto_declare("solver.iterations", 1); + auto_declare("solver.publish_state_feedback", false); m_initialized = true; } return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; @@ -121,6 +124,7 @@ controller_interface::return_type CartesianControllerBase::init(const std::strin auto_declare>("command_interfaces", std::vector()); auto_declare("solver.error_scale", 1.0); auto_declare("solver.iterations", 1); + auto_declare("solver.publish_state_feedback", false); m_initialized = true; } @@ -255,6 +259,17 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Cartes } } + // Controller-internal state publishing + m_feedback_pose_publisher = + std::make_shared >( + get_node()->create_publisher( + std::string(get_node()->get_name()) + "/current_pose", 3)); + + m_feedback_twist_publisher = + std::make_shared >( + get_node()->create_publisher( + std::string(get_node()->get_name()) + "/current_twist", 3)); + m_configured = true; return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; @@ -335,6 +350,11 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Cartes void CartesianControllerBase::writeJointControlCmds() { + if (get_node()->get_parameter("solver.publish_state_feedback").as_bool()) + { + publishStateFeedback(); + } + // Write all available types. for (const auto& type : m_cmd_interface_types) { @@ -456,4 +476,43 @@ ctrl::Vector6D CartesianControllerBase::displayInTipLink(const ctrl::Vector6D& v return out; } +void CartesianControllerBase::publishStateFeedback() +{ + // End-effector pose + auto pose = m_ik_solver->getEndEffectorPose(); + if (m_feedback_pose_publisher->trylock()){ + m_feedback_pose_publisher->msg_.header.stamp = get_node()->now(); + m_feedback_pose_publisher->msg_.header.frame_id = m_robot_base_link; + m_feedback_pose_publisher->msg_.pose.position.x = pose.p.x(); + m_feedback_pose_publisher->msg_.pose.position.y = pose.p.y(); + m_feedback_pose_publisher->msg_.pose.position.z = pose.p.z(); + + pose.M.GetQuaternion( + m_feedback_pose_publisher->msg_.pose.orientation.x, + m_feedback_pose_publisher->msg_.pose.orientation.y, + m_feedback_pose_publisher->msg_.pose.orientation.z, + m_feedback_pose_publisher->msg_.pose.orientation.w + ); + + m_feedback_pose_publisher->unlockAndPublish(); + } + + // End-effector twist + auto twist = m_ik_solver->getEndEffectorVel(); + if (m_feedback_twist_publisher->trylock()){ + m_feedback_twist_publisher->msg_.header.stamp = get_node()->now(); + m_feedback_twist_publisher->msg_.header.frame_id = m_robot_base_link; + m_feedback_twist_publisher->msg_.twist.linear.x = twist[0]; + m_feedback_twist_publisher->msg_.twist.linear.y = twist[1]; + m_feedback_twist_publisher->msg_.twist.linear.z = twist[2]; + m_feedback_twist_publisher->msg_.twist.angular.x = twist[3]; + m_feedback_twist_publisher->msg_.twist.angular.y = twist[4]; + m_feedback_twist_publisher->msg_.twist.angular.z = twist[5]; + + m_feedback_twist_publisher->unlockAndPublish(); + } + +} + + } // namespace diff --git a/cartesian_controller_simulation/config/controller_manager.yaml b/cartesian_controller_simulation/config/controller_manager.yaml index fc19759c..aff9752b 100644 --- a/cartesian_controller_simulation/config/controller_manager.yaml +++ b/cartesian_controller_simulation/config/controller_manager.yaml @@ -90,6 +90,7 @@ cartesian_compliance_controller: solver: error_scale: 0.5 iterations: 1 + publish_state_feedback: True # For all controllers, these gains are w.r.t. the robot_base_link coordinates. pd_gains: @@ -122,6 +123,7 @@ cartesian_force_controller: solver: error_scale: 0.5 + publish_state_feedback: True pd_gains: trans_x: {p: 0.05} @@ -153,6 +155,7 @@ cartesian_motion_controller: solver: error_scale: 1.0 iterations: 10 + publish_state_feedback: True pd_gains: trans_x: {p: 1.0} diff --git a/resources/doc/Solver_details.md b/resources/doc/Solver_details.md index 9ce67904..344a59a1 100644 --- a/resources/doc/Solver_details.md +++ b/resources/doc/Solver_details.md @@ -39,7 +39,7 @@ Unfortunately, there won't exist ideal parameters for every use case and robot. So, for your specific application, you will be tweaking the PD gains at some point. ### Solver parameters -The common solver has two parameters: +The common solver has several parameters: * **iterations**: The number of internally simulated cycles per control cycle. Increasing this number will give the solver more iterations to approach the given target. A value of `10` is a good default for the `CartesianMotionController` and the `CartesianComplianceController`. @@ -51,11 +51,39 @@ The common solver has two parameters: Use this parameter to find the right range for your PD gains. It's handy to use the slider in dynamic reconfigure for this. +* **publish_state_feedback**: A boolean flag whether to publish the + controller-internal state. This is helpful for comparing the controllers' + feedback against the given target reference during parameter tweaking. If + `true`, each controller will publish its end-effector pose and twist on the local topics `current_pose` and + `current_twist`, respectively. You can easily find them in a sourced terminal with + ```bash + ros2 topic list | grep current + ``` + +All solver parameters can be set online via `dynamic_reconfigure` in the controllers' +`solver` namespace, or at startup via the controller's `.yaml` configuration +file, e.g. with +```yaml +my_cartesian_controller: + ros__parameters: + + # link and joints specification here + # ... + + solver: + error_scale: 0.5 + iterations: 5 + publish_state_feedback: True + + # Further specification + # ... +``` + ## Performance As a default, please build the cartesian_controllers in release mode: ```bash -catkin_make -DCMAKE_BUILD_TYPE=Release +colcon build --packages-skip cartesian_controller_simulation cartesian_controller_tests --cmake-args -DCMAKE_BUILD_TYPE=Release ``` The forward dynamics implementation heavily relies on orocos_kinematics_dynamics (KDL), which use Eigen for linear algebra.