Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix after kinematics_interface API break (v1.1.0 -> v1.2.0) #46

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
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
4 changes: 2 additions & 2 deletions cartesian_controllers_ros2.repos
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@ repositories:
external/dynamics_interface:
type: git
url: https://github.com/tpoignonec/dynamics_interface.git
version: main
version: tpoignonec-refractor_for_kinematics_interface_1.2.0

external/ros-controls/kinematics_interface:
type: git
url: https://github.com/ros-controls/kinematics_interface.git
version: 1.1.0
version: master
13 changes: 11 additions & 2 deletions cartesian_state_broadcaster/src/cartesian_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,16 @@ CallbackReturn CartesianStateBroadcaster::on_configure(
auto kinematics_plugin_package =
get_node()->get_parameter("kinematics_plugin_package").as_string();

// Load URDF
auto robot_param = rclcpp::Parameter();
if (!get_node()->get_parameter("robot_description", robot_param)) {
RCLCPP_ERROR(
rclcpp::get_logger("CartesianStateBroadcaster"),
"parameter robot_description not set");
return CallbackReturn::ERROR;
}
auto robot_description = robot_param.as_string();

// Load the differential IK plugin
if (!kinematics_plugin_name.empty()) {
try {
Expand All @@ -62,8 +72,7 @@ CallbackReturn CartesianStateBroadcaster::on_configure(
kinematics_ = std::unique_ptr<kinematics_interface::KinematicsInterface>(
kinematics_loader_->createUnmanagedInstance(kinematics_plugin_name));
if (!kinematics_->initialize(
get_node()->get_node_parameters_interface(),
end_effector_name_))
robot_description, get_node()->get_node_parameters_interface(), "kinematics"))
{
RCLCPP_ERROR(
rclcpp::get_logger("CartesianStateBroadcaster"),
Expand Down
13 changes: 12 additions & 1 deletion cartesian_vic_controller/src/cartesian_vic_rule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,15 @@ CartesianVicRule::configure(
num_joints_ = num_joints;
// reset vic state
reset(num_joints);

// Load URDF
auto robot_param = rclcpp::Parameter();
if (!parameters_interface->get_parameter("robot_description", robot_param)) {
RCLCPP_ERROR(logger_, "parameter robot_description not set");
return controller_interface::return_type::ERROR;
}
auto robot_description = robot_param.as_string();

// Load the dynamics (also used for IK) plugin
if (!parameters_.dynamics.plugin_name.empty()) {
try {
Expand All @@ -70,7 +79,9 @@ CartesianVicRule::configure(
"dynamics_interface::DynamicsInterface");
dynamics_ = std::unique_ptr<dynamics_interface::DynamicsInterface>(
dynamics_loader_->createUnmanagedInstance(parameters_.dynamics.plugin_name));
if (!dynamics_->initialize(parameters_interface, parameters_.dynamics.tip)) {
if (!dynamics_->initialize(
robot_description, parameters_interface, "dynamics"))
{
return controller_interface::return_type::ERROR;
}
} catch (pluginlib::PluginlibException & ex) {
Expand Down
Loading