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

ScaledJTC - Added support for setting speedscaling factor via topic #871

Closed
wants to merge 4 commits into from
Closed
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
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,15 @@
#include "rclcpp/duration.hpp"
#include "scaled_joint_trajectory_controller_parameters.hpp"

#include <std_msgs/msg/float64.hpp>

namespace ur_controllers
{
class ScaledJointTrajectoryController : public joint_trajectory_controller::JointTrajectoryController
{
public:
using ScalingFactorMsg = std_msgs::msg::Float64;

ScaledJointTrajectoryController() = default;
~ScaledJointTrajectoryController() override = default;

Expand All @@ -73,11 +77,13 @@ class ScaledJointTrajectoryController : public joint_trajectory_controller::Join
};

private:
double scaling_factor_{};
double scaling_factor_{ 1.0 };
realtime_tools::RealtimeBuffer<TimeData> time_data_;

std::shared_ptr<scaled_joint_trajectory_controller::ParamListener> scaled_param_listener_;
scaled_joint_trajectory_controller::Params scaled_params_;

rclcpp::Subscription<ScalingFactorMsg>::SharedPtr scaling_factor_sub_;
};
} // namespace ur_controllers

Expand Down
24 changes: 18 additions & 6 deletions ur_controllers/src/scaled_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,23 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
{
controller_interface::InterfaceConfiguration conf;
conf = JointTrajectoryController::state_interface_configuration();
conf.names.push_back(scaled_params_.speed_scaling_interface_name);
if (!scaled_params_.use_speed_scaling_topic_instead)
conf.names.push_back(scaled_params_.speed_scaling_interface_name);

return conf;
}

controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activate(const rclcpp_lifecycle::State& state)
{
if (scaled_params_.use_speed_scaling_topic_instead) {
auto qos = rclcpp::QoS(10);
qos.transient_local();

scaling_factor_sub_ = get_node()->create_subscription<ScalingFactorMsg>(
scaled_params_.speed_scaling_topic_name, qos,
[&](const ScalingFactorMsg& msg) { scaling_factor_ = std::clamp(msg.data / 100.0, 0.0, 1.0); });
}

TimeData time_data;
time_data.time = get_node()->now();
time_data.period = rclcpp::Duration::from_nanoseconds(0);
Expand All @@ -76,11 +86,13 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activat
controller_interface::return_type ScaledJointTrajectoryController::update(const rclcpp::Time& time,
const rclcpp::Duration& period)
{
if (state_interfaces_.back().get_name() == scaled_params_.speed_scaling_interface_name) {
scaling_factor_ = state_interfaces_.back().get_value();
} else {
RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
scaled_params_.speed_scaling_interface_name.c_str());
if (!scaled_params_.use_speed_scaling_topic_instead) {
if (state_interfaces_.back().get_name() == scaled_params_.speed_scaling_interface_name) {
scaling_factor_ = state_interfaces_.back().get_value();
} else {
RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.",
scaled_params_.speed_scaling_interface_name.c_str());
}
}

if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,13 @@ scaled_joint_trajectory_controller:
default_value: "speed_scaling/speed_scaling_factor",
description: "Fully qualified name of the speed scaling interface name"
}
use_speed_scaling_topic_instead: {
type: bool,
default_value: false,
description: "Instead of using the speed_scaling_interface_name listen on <speed_scaling_topic_name>"
}
speed_scaling_topic_name: {
type: string,
default_value: "~/speed_scaling_factor",
description: "Topic name for the speed scaling factor (if enabled)"
}