Skip to content
Open
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
21 changes: 10 additions & 11 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@ find_package(Eigen3 REQUIRED)
find_package(pinocchio REQUIRED)
find_package(realtime_tools REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(generate_parameter_library REQUIRED)

generate_parameter_library(
Expand All @@ -69,20 +71,15 @@ generate_parameter_library(
)

generate_parameter_library(
pose_broadcaster_parameters
src/pose_broadcaster.yaml
state_broadcaster_parameters
src/state_broadcaster.yaml
)

generate_parameter_library(
torque_feedback_controller_parameters
src/torque_feedback_controller.yaml
)

generate_parameter_library(
twist_broadcaster_parameters
src/twist_broadcaster.yaml
)

generate_parameter_library(
cartesian_admittance_controller_parameters
src/cartesian_admittance_controller.yaml
Expand All @@ -93,9 +90,8 @@ add_library(
SHARED
src/cartesian_controller.cpp
src/cartesian_admittance_controller.cpp
src/pose_broadcaster.cpp
src/state_broadcaster.cpp
src/torque_feedback_controller.cpp
src/twist_broadcaster.cpp
)

target_link_libraries(${PROJECT_NAME}
Expand All @@ -121,9 +117,8 @@ target_link_libraries(${PROJECT_NAME}
PRIVATE
cartesian_controller_parameters
cartesian_admittance_controller_parameters
pose_broadcaster_parameters
state_broadcaster_parameters
torque_feedback_controller_parameters
twist_broadcaster_parameters
)


Expand All @@ -138,6 +133,8 @@ ament_target_dependencies(${PROJECT_NAME}
generate_parameter_library
realtime_tools
std_msgs
geometry_msgs
sensor_msgs
)

pluginlib_export_plugin_description_file(
Expand Down Expand Up @@ -166,6 +163,8 @@ ament_export_dependencies(
pinocchio
realtime_tools
std_msgs
geometry_msgs
sensor_msgs
generate_parameter_library
)

Expand Down
12 changes: 3 additions & 9 deletions crisp_controllers.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
Cartesian admittance controller with impedance outer loop for compliant force-based interaction.
</description>
</class>
<class name="crisp_controllers/PoseBroadcaster"
type="crisp_controllers::PoseBroadcaster" base_class_type="controller_interface::ControllerInterface">
<class name="crisp_controllers/StateBroadcaster"
type="crisp_controllers::StateBroadcaster" base_class_type="controller_interface::ControllerInterface">
<description>
Simple broadcaster for the pose.
Broadcaster for joint, Cartesian pose, twist, and wrench state outputs.
</description>
</class>
<class name="crisp_controllers/TorqueFeedbackController"
Expand All @@ -23,10 +23,4 @@
Torque feedback controller for robotic manipulators that responds to external torques with PD control and friction compensation.
</description>
</class>
<class name="crisp_controllers/TwistBroadcaster"
type="crisp_controllers::TwistBroadcaster" base_class_type="controller_interface::ControllerInterface">
<description>
Simple broadcaster for the twist velocity.
</description>
</class>
</library>
14 changes: 14 additions & 0 deletions include/crisp_controllers/cartesian_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <pinocchio/algorithm/kinematics.hpp>
#include <pinocchio/multibody/fwd.hpp>
#include <rclcpp/rclcpp.hpp>
#include <realtime_tools/realtime_publisher.hpp>

#include <crisp_controllers/utils/ros2_version.hpp>

Expand Down Expand Up @@ -106,6 +107,14 @@ class CartesianController : public controller_interface::ControllerInterface {
/** @brief Subscription for variable stiffness messages */
rclcpp::Subscription<std_msgs::msg::Float64MultiArray>::SharedPtr stiffness_sub_;

/** @brief Publisher for commanded joint effort values */
rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr effort_publisher_;
/** @brief Realtime publisher for commanded joint effort values */
std::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::msg::Float64MultiArray>>
realtime_effort_publisher_;
/** @brief Pre-sized commanded effort message for realtime publication */
std_msgs::msg::Float64MultiArray effort_msg_;

/** @brief Flag to indicate if multiple publishers detected */
bool multiple_publishers_detected_;

Expand Down Expand Up @@ -274,6 +283,11 @@ class CartesianController : public controller_interface::ControllerInterface {
/** @brief Final desired torque command */
Eigen::VectorXd tau_d;

/** @brief Time accumulated since the last effort publication */
rclcpp::Duration publish_elapsed_{0, 0};
/** @brief Effort publication interval */
rclcpp::Duration publish_interval_{0, 0};

/** @brief Inverse of the manipulator joint mass projected in Cartesian space (6x6) */
Eigen::Matrix<double, 6, 6> Mx_inv = Eigen::Matrix<double, 6, 6>::Zero();
/** @brief the manipulator joint mass projected in Cartesian space (6x6) */
Expand Down
77 changes: 0 additions & 77 deletions include/crisp_controllers/pose_broadcaster.hpp

This file was deleted.

Loading
Loading